Skip to content

Commit 04afc02

Browse files
committed
Publish nav_msgs::Path
1 parent 57d7ef6 commit 04afc02

File tree

4 files changed

+48
-0
lines changed

4 files changed

+48
-0
lines changed

polygon_coverage_ros/include/polygon_coverage_ros/polygon_planner_base.h

+1
Original file line numberDiff line numberDiff line change
@@ -116,6 +116,7 @@ class PolygonPlannerBase {
116116
// Publishers and Services
117117
ros::Publisher marker_pub_;
118118
ros::Publisher waypoint_list_pub_;
119+
ros::Publisher path_pub_;
119120
ros::Subscriber clicked_point_sub_;
120121
ros::Subscriber polygon_sub_;
121122
ros::ServiceServer set_polygon_srv_;

polygon_coverage_ros/include/polygon_coverage_ros/ros_interface.h

+11
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include <eigen_conversions/eigen_msg.h>
2727
#include <geometry_msgs/Polygon.h>
2828
#include <geometry_msgs/PoseArray.h>
29+
#include <nav_msgs/Path.h>
2930
#include <mav_msgs/conversions.h>
3031
#include <polygon_coverage_msgs/PolygonWithHolesStamped.h>
3132
#include <trajectory_msgs/MultiDOFJointTrajectory.h>
@@ -73,11 +74,21 @@ void poseArrayMsgFromEigenTrajectoryPointVector(
7374
const std::string& frame_id,
7475
geometry_msgs::PoseArray* trajectory_points_pose_array);
7576

77+
void pathMsgFromEigenTrajectoryPointVector(
78+
const mav_msgs::EigenTrajectoryPointVector& trajectory_points,
79+
const std::string& frame_id,
80+
nav_msgs::Path* trajectory_points_path);
81+
7682
void poseArrayMsgFromPath(
7783
const std::vector<Point_2>& waypoints, double altitude,
7884
const std::string& frame_id,
7985
geometry_msgs::PoseArray* trajectory_points_pose_array);
8086

87+
void pathMsgFromPath(
88+
const std::vector<Point_2>& waypoints, double altitude,
89+
const std::string& frame_id,
90+
nav_msgs::Path* trajectory_points_path);
91+
8192
void msgMultiDofJointTrajectoryFromPath(
8293
const std::vector<Point_2>& waypoints, double altitude,
8394
trajectory_msgs::MultiDOFJointTrajectory* msg);

polygon_coverage_ros/src/polygon_planner_base.cc

+7
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
#include <polygon_coverage_planners/cost_functions/path_cost_functions.h>
2727

2828
#include <geometry_msgs/PoseArray.h>
29+
#include <nav_msgs/Path.h>
2930
#include <visualization_msgs/MarkerArray.h>
3031

3132
namespace polygon_coverage_planning {
@@ -59,6 +60,8 @@ void PolygonPlannerBase::advertiseTopics() {
5960
"path_markers", 1, true);
6061
waypoint_list_pub_ = nh_.advertise<geometry_msgs::PoseArray>(
6162
"waypoint_list", 1, latch_topics_);
63+
path_pub_ = nh_.advertise<nav_msgs::Path>(
64+
"path", 1, latch_topics_);
6265
// Services for generating the plan.
6366
set_polygon_srv_ = nh_private_.advertiseService(
6467
"set_polygon", &PolygonPlannerBase::setPolygonCallback, this);
@@ -311,15 +314,19 @@ bool PolygonPlannerBase::publishTrajectoryPoints() {
311314

312315
// Convert path to pose array.
313316
geometry_msgs::PoseArray trajectory_points_pose_array;
317+
nav_msgs::Path trajectory_points_path;
314318
if (!altitude_.has_value()) {
315319
ROS_WARN_STREAM("Cannot send trajectory because altitude not set.");
316320
return false;
317321
}
318322
poseArrayMsgFromPath(solution_, altitude_.value(), global_frame_id_,
319323
&trajectory_points_pose_array);
324+
pathMsgFromPath(solution_, altitude_.value(), global_frame_id_,
325+
&trajectory_points_path);
320326

321327
// Publishing
322328
waypoint_list_pub_.publish(trajectory_points_pose_array);
329+
path_pub_.publish(trajectory_points_path);
323330

324331
// Success
325332
return true;

polygon_coverage_ros/src/ros_interface.cc

+29
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,23 @@ void poseArrayMsgFromEigenTrajectoryPointVector(
6666
}
6767
}
6868

69+
void pathMsgFromEigenTrajectoryPointVector(
70+
const mav_msgs::EigenTrajectoryPointVector& trajectory_points,
71+
const std::string& frame_id,
72+
nav_msgs::Path* trajectory_points_path) {
73+
ROS_ASSERT(trajectory_points_pose_array);
74+
75+
// Header
76+
trajectory_points_path->header.frame_id = frame_id;
77+
// Converting and populating the message with all points
78+
for (const mav_msgs::EigenTrajectoryPoint& trajectory_point :
79+
trajectory_points) {
80+
geometry_msgs::PoseStamped msg;
81+
mav_msgs::msgPoseStampedFromEigenTrajectoryPoint(trajectory_point, &msg);
82+
trajectory_points_path->poses.push_back(msg);
83+
}
84+
}
85+
6986
void poseArrayMsgFromPath(
7087
const std::vector<Point_2>& waypoints, double altitude,
7188
const std::string& frame_id,
@@ -78,6 +95,18 @@ void poseArrayMsgFromPath(
7895
trajectory_points_pose_array);
7996
}
8097

98+
void pathMsgFromPath(
99+
const std::vector<Point_2>& waypoints, double altitude,
100+
const std::string& frame_id,
101+
nav_msgs::Path* trajectory_points_path) {
102+
ROS_ASSERT(trajectory_points_path);
103+
104+
mav_msgs::EigenTrajectoryPointVector eigen_traj;
105+
eigenTrajectoryPointVectorFromPath(waypoints, altitude, &eigen_traj);
106+
pathMsgFromEigenTrajectoryPointVector(eigen_traj, frame_id,
107+
trajectory_points_path);
108+
}
109+
81110
void msgMultiDofJointTrajectoryFromPath(
82111
const std::vector<Point_2>& waypoints, double altitude,
83112
trajectory_msgs::MultiDOFJointTrajectory* msg) {

0 commit comments

Comments
 (0)