Skip to content

Commit 14951b9

Browse files
authored
Merge pull request #59 from ethz-asl/feature/remove_mav_msgs
Remove mav_msgs dependency.
2 parents 040094c + 8b7fe09 commit 14951b9

File tree

6 files changed

+77
-103
lines changed

6 files changed

+77
-103
lines changed

install/dependencies.rosinstall

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
- git: {local-name: catkin_simple, uri: 'git@github.com:catkin/catkin_simple.git', version: 0e62848b12da76c8cc58a1add42b4f894d1ac21e}
22
- git: {local-name: cgal_catkin, uri: 'git@github.com:ethz-asl/cgal_catkin.git', version: releases/CGAL-5.0.3}
3-
- git: {local-name: polygon_coverage_planning, uri: 'git@github.com:ethz-asl/polygon_coverage_planning.git', version: v2.0.2}
3+
- git: {local-name: polygon_coverage_planning, uri: 'git@github.com:ethz-asl/polygon_coverage_planning.git', version: v2.0.3}
Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
- git: {local-name: catkin_simple, uri: 'https://github.com/catkin/catkin_simple.git', version: 0e62848b12da76c8cc58a1add42b4f894d1ac21e}
22
- git: {local-name: cgal_catkin, uri: 'https://github.com/ethz-asl/cgal_catkin.git', version: releases/CGAL-5.0.3}
3-
- git: {local-name: polygon_coverage_planning, uri: 'https://github.com/ethz-asl/polygon_coverage_planning.git', version: v2.0.2}
3+
- git: {local-name: polygon_coverage_planning, uri: 'https://github.com/ethz-asl/polygon_coverage_planning.git', version: v2.0.3}

install/prepare-jenkins-slave.sh

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,8 +7,6 @@ echo "ROS version: ${ROS_VERSION}"
77
sudo apt-get install -y python-wstool python-catkin-tools
88

99
# Package dependencies.
10-
echo "Installing MAV_COMM dependencies."
11-
sudo apt-get install -y ros-${ROS_VERSION}-mav-msgs
1210
echo "Installing CGAL dependencies."
1311
sudo apt-get install -y libgmp-dev libmpfr-dev
1412
echo "Installing MONO dependencies."

polygon_coverage_ros/include/polygon_coverage_ros/ros_interface.h

Lines changed: 8 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -25,15 +25,13 @@
2525

2626
#include <eigen_conversions/eigen_msg.h>
2727
#include <geometry_msgs/Polygon.h>
28+
#include <geometry_msgs/Pose.h>
2829
#include <geometry_msgs/PoseArray.h>
29-
#include <mav_msgs/conversions.h>
3030
#include <polygon_coverage_msgs/PolygonWithHolesStamped.h>
3131
#include <trajectory_msgs/MultiDOFJointTrajectory.h>
3232
#include <visualization_msgs/Marker.h>
3333
#include <visualization_msgs/MarkerArray.h>
3434

35-
#include <mav_msgs/eigen_mav_msgs.h>
36-
3735
#include <polygon_coverage_geometry/cgal_definitions.h>
3836

3937
namespace polygon_coverage_planning {
@@ -64,15 +62,6 @@ class Color : public std_msgs::ColorRGBA {
6462
};
6563

6664
// Warning: Does not set frame or time stamps or orientation.
67-
void eigenTrajectoryPointVectorFromPath(
68-
const std::vector<Point_2>& waypoints, double altitude,
69-
mav_msgs::EigenTrajectoryPointVector* traj_points);
70-
71-
void poseArrayMsgFromEigenTrajectoryPointVector(
72-
const mav_msgs::EigenTrajectoryPointVector& trajectory_points,
73-
const std::string& frame_id,
74-
geometry_msgs::PoseArray* trajectory_points_pose_array);
75-
7665
void poseArrayMsgFromPath(
7766
const std::vector<Point_2>& waypoints, double altitude,
7867
const std::string& frame_id,
@@ -82,6 +71,9 @@ void msgMultiDofJointTrajectoryFromPath(
8271
const std::vector<Point_2>& waypoints, double altitude,
8372
trajectory_msgs::MultiDOFJointTrajectory* msg);
8473

74+
void msgPointFromWaypoint(const Point_2& waypoint, double altitude,
75+
geometry_msgs::Point* point);
76+
8577
void createMarkers(const std::vector<Point_2>& vertices, double altitude,
8678
const std::string& frame_id, const std::string& ns,
8779
const Color& points_color, const Color& lines_color,
@@ -106,8 +98,8 @@ void createStartAndEndPointMarkers(const Point_2& start, const Point_2& end,
10698
visualization_msgs::Marker* start_point,
10799
visualization_msgs::Marker* end_point);
108100

109-
void createStartAndEndPointMarkers(const mav_msgs::EigenTrajectoryPoint& start,
110-
const mav_msgs::EigenTrajectoryPoint& end,
101+
void createStartAndEndPointMarkers(const geometry_msgs::Pose& start,
102+
const geometry_msgs::Pose& end,
111103
const std::string& frame_id,
112104
const std::string& ns,
113105
visualization_msgs::Marker* start_point,
@@ -119,8 +111,8 @@ void createStartAndEndTextMarkers(const Point_2& start, const Point_2& end,
119111
visualization_msgs::Marker* start_text,
120112
visualization_msgs::Marker* end_text);
121113

122-
void createStartAndEndTextMarkers(const mav_msgs::EigenTrajectoryPoint& start,
123-
const mav_msgs::EigenTrajectoryPoint& end,
114+
void createStartAndEndTextMarkers(const geometry_msgs::Pose& start,
115+
const geometry_msgs::Pose& end,
124116
const std::string& frame_id,
125117
const std::string& ns,
126118
visualization_msgs::Marker* start_text,

polygon_coverage_ros/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616
<depend>roscpp</depend>
1717

1818
<depend>nav_msgs</depend>
19-
<depend>mav_msgs</depend>
2019
<depend>geometry_msgs</depend>
2120
<depend>trajectory_msgs</depend>
2221
<depend>visualization_msgs</depend>

polygon_coverage_ros/src/ros_interface.cc

Lines changed: 67 additions & 82 deletions
Original file line numberDiff line numberDiff line change
@@ -35,57 +35,56 @@
3535

3636
namespace polygon_coverage_planning {
3737

38-
void eigenTrajectoryPointVectorFromPath(
39-
const std::vector<Point_2>& waypoints, double altitude,
40-
mav_msgs::EigenTrajectoryPointVector* traj_points) {
41-
ROS_ASSERT(traj_points);
42-
43-
traj_points->clear();
44-
traj_points->resize(waypoints.size());
38+
void poseArrayMsgFromPath(const std::vector<Point_2>& waypoints,
39+
double altitude, const std::string& frame_id,
40+
geometry_msgs::PoseArray* pose_array) {
41+
ROS_ASSERT(pose_array);
42+
43+
pose_array->header.frame_id = frame_id;
44+
pose_array->poses.clear();
45+
pose_array->poses.resize(waypoints.size());
4546
for (size_t i = 0; i < waypoints.size(); i++) {
46-
(*traj_points)[i].position_W =
47-
Eigen::Vector3d(CGAL::to_double(waypoints[i].x()),
48-
CGAL::to_double(waypoints[i].y()), altitude);
47+
msgPointFromWaypoint(waypoints[i], altitude,
48+
&pose_array->poses[i].position);
4949
}
5050
}
5151

52-
void poseArrayMsgFromEigenTrajectoryPointVector(
53-
const mav_msgs::EigenTrajectoryPointVector& trajectory_points,
54-
const std::string& frame_id,
55-
geometry_msgs::PoseArray* trajectory_points_pose_array) {
56-
ROS_ASSERT(trajectory_points_pose_array);
57-
58-
// Header
59-
trajectory_points_pose_array->header.frame_id = frame_id;
60-
// Converting and populating the message with all points
61-
for (const mav_msgs::EigenTrajectoryPoint& trajectory_point :
62-
trajectory_points) {
63-
geometry_msgs::PoseStamped msg;
64-
mav_msgs::msgPoseStampedFromEigenTrajectoryPoint(trajectory_point, &msg);
65-
trajectory_points_pose_array->poses.push_back(msg.pose);
66-
}
67-
}
68-
69-
void poseArrayMsgFromPath(
70-
const std::vector<Point_2>& waypoints, double altitude,
71-
const std::string& frame_id,
72-
geometry_msgs::PoseArray* trajectory_points_pose_array) {
73-
ROS_ASSERT(trajectory_points_pose_array);
74-
75-
mav_msgs::EigenTrajectoryPointVector eigen_traj;
76-
eigenTrajectoryPointVectorFromPath(waypoints, altitude, &eigen_traj);
77-
poseArrayMsgFromEigenTrajectoryPointVector(eigen_traj, frame_id,
78-
trajectory_points_pose_array);
79-
}
80-
8152
void msgMultiDofJointTrajectoryFromPath(
8253
const std::vector<Point_2>& waypoints, double altitude,
8354
trajectory_msgs::MultiDOFJointTrajectory* msg) {
8455
ROS_ASSERT(msg);
8556

86-
mav_msgs::EigenTrajectoryPointVector eigen_traj;
87-
eigenTrajectoryPointVectorFromPath(waypoints, altitude, &eigen_traj);
88-
mav_msgs::msgMultiDofJointTrajectoryFromEigen(eigen_traj, msg);
57+
geometry_msgs::PoseArray pose_array;
58+
poseArrayMsgFromPath(waypoints, altitude, "", &pose_array);
59+
60+
msg->header = pose_array.header;
61+
msg->joint_names.clear();
62+
msg->joint_names.push_back("base_link");
63+
msg->points.clear();
64+
65+
for (const auto& pose : pose_array.poses) {
66+
trajectory_msgs::MultiDOFJointTrajectoryPoint point_msg;
67+
point_msg.transforms.resize(1);
68+
point_msg.velocities.resize(1);
69+
point_msg.accelerations.resize(1);
70+
71+
point_msg.transforms[0].translation.x = pose.position.x;
72+
point_msg.transforms[0].translation.y = pose.position.y;
73+
point_msg.transforms[0].translation.z = pose.position.z;
74+
75+
point_msg.transforms[0].rotation.w = 1.0;
76+
77+
msg->points.push_back(point_msg);
78+
}
79+
}
80+
81+
void msgPointFromWaypoint(const Point_2& waypoint, double altitude,
82+
geometry_msgs::Point* point) {
83+
ROS_ASSERT(point);
84+
85+
point->x = CGAL::to_double(waypoint.x());
86+
point->y = CGAL::to_double(waypoint.y());
87+
point->z = altitude;
8988
}
9089

9190
void createMarkers(const std::vector<Point_2>& vertices, double altitude,
@@ -120,9 +119,7 @@ void createMarkers(const std::vector<Point_2>& vertices, double altitude,
120119

121120
for (size_t i = 0; i < vertices.size(); i++) {
122121
geometry_msgs::Point p;
123-
p.x = CGAL::to_double(vertices[i].x());
124-
p.y = CGAL::to_double(vertices[i].y());
125-
p.z = altitude;
122+
msgPointFromWaypoint(vertices[i], altitude, &p);
126123

127124
points->points.push_back(p);
128125
line_strip->points.push_back(p);
@@ -167,22 +164,21 @@ void createStartAndEndPointMarkers(const Point_2& start, const Point_2& end,
167164
const std::string& ns,
168165
visualization_msgs::Marker* start_point,
169166
visualization_msgs::Marker* end_point) {
170-
mav_msgs::EigenTrajectoryPoint eigen_start;
171-
eigen_start.position_W.x() = CGAL::to_double(start.x());
172-
eigen_start.position_W.y() = CGAL::to_double(start.y());
173-
eigen_start.position_W.z() = altitude;
167+
ROS_ASSERT(start_point);
168+
ROS_ASSERT(end_point);
174169

175-
mav_msgs::EigenTrajectoryPoint eigen_end;
176-
eigen_end.position_W.x() = CGAL::to_double(end.x());
177-
eigen_end.position_W.y() = CGAL::to_double(end.y());
178-
eigen_end.position_W.z() = altitude;
170+
geometry_msgs::Pose start_pose;
171+
msgPointFromWaypoint(start, altitude, &start_pose.position);
179172

180-
return createStartAndEndPointMarkers(eigen_start, eigen_end, frame_id, ns,
173+
geometry_msgs::Pose end_pose;
174+
msgPointFromWaypoint(end, altitude, &end_pose.position);
175+
176+
return createStartAndEndPointMarkers(start_pose, end_pose, frame_id, ns,
181177
start_point, end_point);
182178
}
183179

184-
void createStartAndEndPointMarkers(const mav_msgs::EigenTrajectoryPoint& start,
185-
const mav_msgs::EigenTrajectoryPoint& end,
180+
void createStartAndEndPointMarkers(const geometry_msgs::Pose& start,
181+
const geometry_msgs::Pose& end,
186182
const std::string& frame_id,
187183
const std::string& ns,
188184
visualization_msgs::Marker* start_point,
@@ -196,12 +192,8 @@ void createStartAndEndPointMarkers(const mav_msgs::EigenTrajectoryPoint& start,
196192
end_point->ns = ns + "_end";
197193
start_point->action = end_point->action = visualization_msgs::Marker::ADD;
198194

199-
geometry_msgs::PoseStamped start_stamped, end_stamped;
200-
msgPoseStampedFromEigenTrajectoryPoint(start, &start_stamped);
201-
msgPoseStampedFromEigenTrajectoryPoint(end, &end_stamped);
202-
203-
start_point->pose = start_stamped.pose;
204-
end_point->pose = end_stamped.pose;
195+
start_point->pose = start;
196+
end_point->pose = end;
205197

206198
start_point->pose.orientation.w = end_point->pose.orientation.w = 1.0;
207199

@@ -225,22 +217,21 @@ void createStartAndEndTextMarkers(const Point_2& start, const Point_2& end,
225217
const std::string& ns,
226218
visualization_msgs::Marker* start_text,
227219
visualization_msgs::Marker* end_text) {
228-
mav_msgs::EigenTrajectoryPoint eigen_start;
229-
eigen_start.position_W.x() = CGAL::to_double(start.x());
230-
eigen_start.position_W.y() = CGAL::to_double(start.y());
231-
eigen_start.position_W.z() = altitude;
220+
ROS_ASSERT(start_text);
221+
ROS_ASSERT(end_text);
222+
223+
geometry_msgs::Pose start_pose;
224+
msgPointFromWaypoint(start, altitude, &start_pose.position);
232225

233-
mav_msgs::EigenTrajectoryPoint eigen_end;
234-
eigen_end.position_W.x() = CGAL::to_double(end.x());
235-
eigen_end.position_W.y() = CGAL::to_double(end.y());
236-
eigen_end.position_W.z() = altitude;
226+
geometry_msgs::Pose end_pose;
227+
msgPointFromWaypoint(end, altitude, &end_pose.position);
237228

238-
return createStartAndEndTextMarkers(eigen_start, eigen_end, frame_id, ns,
229+
return createStartAndEndTextMarkers(start_pose, end_pose, frame_id, ns,
239230
start_text, end_text);
240231
}
241232

242-
void createStartAndEndTextMarkers(const mav_msgs::EigenTrajectoryPoint& start,
243-
const mav_msgs::EigenTrajectoryPoint& end,
233+
void createStartAndEndTextMarkers(const geometry_msgs::Pose& start,
234+
const geometry_msgs::Pose& end,
244235
const std::string& frame_id,
245236
const std::string& ns,
246237
visualization_msgs::Marker* start_text,
@@ -256,12 +247,8 @@ void createStartAndEndTextMarkers(const mav_msgs::EigenTrajectoryPoint& start,
256247
start_text->type = end_text->type =
257248
visualization_msgs::Marker::TEXT_VIEW_FACING;
258249

259-
geometry_msgs::PoseStamped start_stamped, end_stamped;
260-
msgPoseStampedFromEigenTrajectoryPoint(start, &start_stamped);
261-
msgPoseStampedFromEigenTrajectoryPoint(end, &end_stamped);
262-
263-
start_text->pose = start_stamped.pose;
264-
end_text->pose = end_stamped.pose;
250+
start_text->pose = start;
251+
end_text->pose = end;
265252

266253
start_text->pose.orientation.w = end_text->pose.orientation.w = 1.0;
267254

@@ -364,9 +351,7 @@ void createTriangles(const std::vector<std::vector<Point_2>>& triangles,
364351
ROS_ASSERT(t.size() == 3);
365352
for (const auto& v : t) {
366353
geometry_msgs::Point p;
367-
p.x = CGAL::to_double(v.x());
368-
p.y = CGAL::to_double(v.y());
369-
p.z = altitude;
354+
msgPointFromWaypoint(v, altitude, &p);
370355

371356
markers->points.push_back(p);
372357
}

0 commit comments

Comments
 (0)