3535
3636namespace 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-
8152void 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
9190void 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