41 #include <teb_local_planner/FeedbackMsg.h> 58 ROS_WARN(
"TebVisualization already initialized. Reinitalizing...");
94 nav_msgs::Path teb_path;
99 geometry_msgs::PoseArray teb_poses;
100 teb_poses.header.frame_id = teb_path.header.frame_id;
101 teb_poses.header.stamp = teb_path.header.stamp;
106 geometry_msgs::PoseStamped pose;
107 pose.header.frame_id = teb_path.header.frame_id;
108 pose.header.stamp = teb_path.header.stamp;
109 pose.pose.position.x = teb.
Pose(i).
x();
110 pose.pose.position.y = teb.
Pose(i).
y();
113 teb_path.poses.push_back(pose);
114 teb_poses.poses.push_back(pose.pose);
127 std::vector<visualization_msgs::Marker> markers;
133 for (std::vector<visualization_msgs::Marker>::iterator marker_it = markers.begin(); marker_it != markers.end(); ++marker_it, ++idx)
137 marker_it->action = visualization_msgs::Marker::ADD;
154 visualization_msgs::Marker marker;
157 marker.ns =
"PointObstacles";
159 marker.type = visualization_msgs::Marker::POINTS;
160 marker.action = visualization_msgs::Marker::ADD;
163 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
171 geometry_msgs::Point
point;
172 point.x = pobst->x();
173 point.y = pobst->y();
175 marker.points.push_back(point);
179 marker.type = visualization_msgs::Marker::LINE_LIST;
180 geometry_msgs::Point start;
181 start.x = pobst->x();
182 start.y = pobst->y();
184 marker.points.push_back(start);
186 geometry_msgs::Point end;
188 Eigen::Vector2d pred;
189 pobst->predictCentroidConstantVelocity(t, pred);
193 marker.points.push_back(end);
197 marker.scale.x = 0.1;
198 marker.scale.y = 0.1;
199 marker.color.a = 1.0;
200 marker.color.r = 1.0;
201 marker.color.g = 0.0;
202 marker.color.b = 0.0;
210 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
216 visualization_msgs::Marker marker;
219 marker.ns =
"LineObstacles";
221 marker.type = visualization_msgs::Marker::LINE_STRIP;
222 marker.action = visualization_msgs::Marker::ADD;
224 geometry_msgs::Point start;
225 start.x = pobst->start().x();
226 start.y = pobst->start().y();
228 marker.points.push_back(start);
229 geometry_msgs::Point end;
230 end.x = pobst->end().x();
231 end.y = pobst->end().y();
233 marker.points.push_back(end);
235 marker.scale.x = 0.1;
236 marker.scale.y = 0.1;
237 marker.color.a = 1.0;
238 marker.color.r = 0.0;
239 marker.color.g = 1.0;
240 marker.color.b = 0.0;
250 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
256 visualization_msgs::Marker marker;
259 marker.ns =
"PolyObstacles";
261 marker.type = visualization_msgs::Marker::LINE_STRIP;
262 marker.action = visualization_msgs::Marker::ADD;
265 for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex)
267 geometry_msgs::Point
point;
268 point.x = vertex->x();
269 point.y = vertex->y();
271 marker.points.push_back(point);
276 if (pobst->vertices().size() > 2)
278 geometry_msgs::Point
point;
279 point.x = pobst->vertices().front().x();
280 point.y = pobst->vertices().front().y();
282 marker.points.push_back(point);
284 marker.scale.x = 0.1;
285 marker.scale.y = 0.1;
286 marker.color.a = 1.0;
287 marker.color.r = 1.0;
288 marker.color.g = 0.0;
289 marker.color.b = 0.0;
302 visualization_msgs::Marker marker;
307 marker.type = visualization_msgs::Marker::POINTS;
308 marker.action = visualization_msgs::Marker::ADD;
311 for (std::size_t i=0; i <
via_points.size(); ++i)
313 geometry_msgs::Point
point;
317 marker.points.push_back(point);
320 marker.scale.x = 0.1;
321 marker.scale.y = 0.1;
322 marker.color.a = 1.0;
323 marker.color.r = 0.0;
324 marker.color.g = 0.0;
325 marker.color.b = 1.0;
335 visualization_msgs::Marker marker;
340 marker.type = visualization_msgs::Marker::LINE_LIST;
341 marker.action = visualization_msgs::Marker::ADD;
344 for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb )
347 PoseSequence::const_iterator it_pose = it_teb->get()->teb().poses().begin();
348 TimeDiffSequence::const_iterator it_timediff = it_teb->get()->teb().timediffs().begin();
349 PoseSequence::const_iterator it_pose_end = it_teb->get()->teb().poses().end();
350 std::advance(it_pose_end, -1);
353 while (it_pose != it_pose_end)
355 geometry_msgs::Point point_start;
356 point_start.x = (*it_pose)->x();
357 point_start.y = (*it_pose)->y();
359 marker.points.push_back(point_start);
361 time += (*it_timediff)->dt();
363 geometry_msgs::Point point_end;
364 point_end.x = (*boost::next(it_pose))->
x();
365 point_end.y = (*boost::next(it_pose))->
y();
367 marker.points.push_back(point_end);
372 marker.scale.x = 0.01;
373 marker.color.a = 1.0;
374 marker.color.r = 0.5;
375 marker.color.g = 1.0;
376 marker.color.b = 0.0;
382 unsigned int selected_trajectory_idx,
const ObstContainer& obstacles)
387 msg.selected_trajectory_idx = selected_trajectory_idx;
390 msg.trajectories.resize(teb_planners.size());
393 std::size_t idx_traj = 0;
394 for( TebOptPlannerContainer::const_iterator it_teb = teb_planners.begin(); it_teb != teb_planners.end(); ++it_teb, ++idx_traj )
396 msg.trajectories[idx_traj].header = msg.header;
397 it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory);
401 msg.obstacles_msg.obstacles.resize(obstacles.size());
402 for (std::size_t i=0; i<obstacles.size(); ++i)
404 msg.obstacles_msg.header = msg.header;
407 msg.obstacles_msg.obstacles[i].header = msg.header;
408 obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
411 msg.obstacles_msg.obstacles[i].id = i;
417 obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
428 msg.selected_trajectory_idx = 0;
430 msg.trajectories.resize(1);
431 msg.trajectories.front().header = msg.header;
435 msg.obstacles_msg.obstacles.resize(obstacles.size());
436 for (std::size_t i=0; i<obstacles.size(); ++i)
438 msg.obstacles_msg.header = msg.header;
441 msg.obstacles_msg.obstacles[i].header = msg.header;
442 obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
445 msg.obstacles_msg.obstacles[i].id = i;
451 obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
461 ROS_ERROR(
"TebVisualization class not initialized. You must call initialize or an appropriate constructor");
void publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > &via_points, const std::string &ns="ViaPoints") const
Publish via-points to the ros topic ../../teb_markers.
std::string map_frame
Global planning frame.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
void initialize(ros::NodeHandle &nh, const TebConfig &cfg)
Initializes the class and registers topics.
ros::Publisher feedback_pub_
Publisher for the feedback message for analysis and debug purposes.
void publishLocalPlan(const std::vector< geometry_msgs::PoseStamped > &local_plan) const
Publish a given local plan to the ros topic ../../local_plan.
void publish(const boost::shared_ptr< M > &message) const
ros::Publisher teb_poses_pub_
Publisher for the trajectory pose sequence.
Config class for the teb_local_planner and its components.
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information...
bool printErrorWhenNotInitialized() const
Small helper function that checks if initialize() has been called and prints an error message if not...
double & x()
Access the x-coordinate the pose.
TFSIMD_FORCE_INLINE const tfScalar & y() const
Implements a polygon obstacle with an arbitrary number of vertices.
double visualize_with_time_as_z_axis_scale
If this value is bigger than 0, the trajectory and obstacles are visualized in 3d using the time as t...
Implements a 2D line obstacle.
void publishGlobalPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan) const
Publish a given global plan to the ros topic ../../global_plan.
void publishLocalPlanAndPoses(const TimedElasticBand &teb) const
Publish Timed_Elastic_Band related stuff (local plan, pose sequence).
void publishObstacles(const ObstContainer &obstacles) const
Publish obstacle positions to the ros topic ../../teb_markers.
void publishTebContainer(const std::vector< boost::shared_ptr< TebOptimalPlanner > > &teb_planner, const std::string &ns="TebContainer")
Publish multiple Tebs from a container class (publish as marker message).
struct teb_local_planner::TebConfig::HomotopyClasses hcp
Implements a 2D point obstacle.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
void publishRobotFootprintModel(const PoseSE2 ¤t_pose, const BaseRobotFootprintModel &robot_model, const std::string &ns="RobotFootprintModel")
Publish the visualization of the robot model.
TFSIMD_FORCE_INLINE const tfScalar & x() const
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher teb_marker_pub_
Publisher for visualization markers.
std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer
Abbrev. for containers storing multiple teb optimal planners.
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
double & y()
Access the y-coordinate the pose.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
double & theta()
Access the orientation part (yaw angle) of the pose.
TebVisualization()
Default constructor.
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
ros::Publisher global_plan_pub_
Publisher for the global plan.
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
ros::Publisher local_plan_pub_
Publisher for the local plan.
ViaPointContainer via_points
bool initialized_
Keeps track about the correct initialization of this class.
void publishFeedbackMessage(const std::vector< boost::shared_ptr< TebOptimalPlanner > > &teb_planners, unsigned int selected_trajectory_idx, const ObstContainer &obstacles)
Publish a feedback message (multiple trajectory version)
int sizePoses() const
Get the length of the internal pose sequence.