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);
123 const std_msgs::ColorRGBA &color)
128 std::vector<visualization_msgs::Marker> markers;
134 for (std::vector<visualization_msgs::Marker>::iterator marker_it = markers.begin(); marker_it != markers.end(); ++marker_it, ++idx)
138 marker_it->action = visualization_msgs::Marker::ADD;
160 visualization_msgs::Marker marker;
163 marker.ns =
"PointObstacles";
165 marker.type = visualization_msgs::Marker::POINTS;
166 marker.action = visualization_msgs::Marker::ADD;
169 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
177 geometry_msgs::Point
point;
178 point.x = pobst->x();
179 point.y = pobst->y();
181 marker.points.push_back(point);
185 marker.type = visualization_msgs::Marker::LINE_LIST;
186 geometry_msgs::Point
start;
187 start.x = pobst->x();
188 start.y = pobst->y();
190 marker.points.push_back(start);
192 geometry_msgs::Point end;
194 Eigen::Vector2d pred;
195 pobst->predictCentroidConstantVelocity(t, pred);
199 marker.points.push_back(end);
203 marker.scale.x = 0.1;
204 marker.scale.y = 0.1;
205 marker.color.a = 1.0;
206 marker.color.r = 1.0;
207 marker.color.g = 0.0;
208 marker.color.b = 0.0;
216 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
222 visualization_msgs::Marker marker;
225 marker.ns =
"CircularObstacles";
227 marker.type = visualization_msgs::Marker::SPHERE_LIST;
228 marker.action = visualization_msgs::Marker::ADD;
230 geometry_msgs::Point
point;
231 point.x = pobst->x();
232 point.y = pobst->y();
234 marker.points.push_back(point);
236 marker.scale.x = pobst->radius();
237 marker.scale.y = pobst->radius();
238 marker.color.a = 1.0;
239 marker.color.r = 0.0;
240 marker.color.g = 1.0;
241 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 =
"LineObstacles";
261 marker.type = visualization_msgs::Marker::LINE_STRIP;
262 marker.action = visualization_msgs::Marker::ADD;
264 geometry_msgs::Point
start;
265 start.x = pobst->start().x();
266 start.y = pobst->start().y();
268 marker.points.push_back(start);
269 geometry_msgs::Point end;
270 end.x = pobst->end().x();
271 end.y = pobst->end().y();
273 marker.points.push_back(end);
275 marker.scale.x = 0.1;
276 marker.scale.y = 0.1;
277 marker.color.a = 1.0;
278 marker.color.r = 0.0;
279 marker.color.g = 1.0;
280 marker.color.b = 0.0;
290 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
296 visualization_msgs::Marker marker;
299 marker.ns =
"PolyObstacles";
301 marker.type = visualization_msgs::Marker::LINE_STRIP;
302 marker.action = visualization_msgs::Marker::ADD;
305 for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex)
307 geometry_msgs::Point
point;
308 point.x = vertex->x();
309 point.y = vertex->y();
311 marker.points.push_back(point);
316 if (pobst->vertices().size() > 2)
318 geometry_msgs::Point
point;
319 point.x = pobst->vertices().front().x();
320 point.y = pobst->vertices().front().y();
322 marker.points.push_back(point);
324 marker.scale.x = 0.1;
325 marker.scale.y = 0.1;
326 marker.color.a = 1.0;
327 marker.color.r = 1.0;
328 marker.color.g = 0.0;
329 marker.color.b = 0.0;
342 visualization_msgs::Marker marker;
347 marker.type = visualization_msgs::Marker::POINTS;
348 marker.action = visualization_msgs::Marker::ADD;
351 for (std::size_t i=0; i <
via_points.size(); ++i)
353 geometry_msgs::Point
point;
357 marker.points.push_back(point);
360 marker.scale.x = 0.1;
361 marker.scale.y = 0.1;
362 marker.color.a = 1.0;
363 marker.color.r = 0.0;
364 marker.color.g = 0.0;
365 marker.color.b = 1.0;
375 visualization_msgs::Marker marker;
380 marker.type = visualization_msgs::Marker::LINE_LIST;
381 marker.action = visualization_msgs::Marker::ADD;
384 for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb )
387 PoseSequence::const_iterator it_pose = it_teb->get()->teb().poses().begin();
388 TimeDiffSequence::const_iterator it_timediff = it_teb->get()->teb().timediffs().begin();
389 PoseSequence::const_iterator it_pose_end = it_teb->get()->teb().poses().end();
390 std::advance(it_pose_end, -1);
393 while (it_pose != it_pose_end)
395 geometry_msgs::Point point_start;
396 point_start.x = (*it_pose)->x();
397 point_start.y = (*it_pose)->y();
399 marker.points.push_back(point_start);
401 time += (*it_timediff)->dt();
403 geometry_msgs::Point point_end;
404 point_end.x = (*boost::next(it_pose))->x();
405 point_end.y = (*boost::next(it_pose))->y();
407 marker.points.push_back(point_end);
412 marker.scale.x = 0.01;
413 marker.color.a = 1.0;
414 marker.color.r = 0.5;
415 marker.color.g = 1.0;
416 marker.color.b = 0.0;
422 unsigned int selected_trajectory_idx,
const ObstContainer& obstacles)
427 msg.selected_trajectory_idx = selected_trajectory_idx;
430 msg.trajectories.resize(teb_planners.size());
433 std::size_t idx_traj = 0;
434 for( TebOptPlannerContainer::const_iterator it_teb = teb_planners.begin(); it_teb != teb_planners.end(); ++it_teb, ++idx_traj )
436 msg.trajectories[idx_traj].header = msg.header;
437 it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory);
441 msg.obstacles_msg.obstacles.resize(obstacles.size());
442 for (std::size_t i=0; i<obstacles.size(); ++i)
444 msg.obstacles_msg.header = msg.header;
447 msg.obstacles_msg.obstacles[i].header = msg.header;
448 obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
451 msg.obstacles_msg.obstacles[i].id = i;
457 obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
468 msg.selected_trajectory_idx = 0;
470 msg.trajectories.resize(1);
471 msg.trajectories.front().header = msg.header;
475 msg.obstacles_msg.obstacles.resize(obstacles.size());
476 for (std::size_t i=0; i<obstacles.size(); ++i)
478 msg.obstacles_msg.header = msg.header;
481 msg.obstacles_msg.obstacles[i].header = msg.header;
482 obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
485 msg.obstacles_msg.obstacles[i].id = i;
491 obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
499 std_msgs::ColorRGBA color;
511 ROS_ERROR(
"TebVisualization class not initialized. You must call initialize or an appropriate constructor");
Implements a 2D circular obstacle (point obstacle plus radius)
std::string map_frame
Global planning frame.
bool printErrorWhenNotInitialized() const
Small helper function that checks if initialize() has been called and prints an error message if not...
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 getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
ros::Publisher teb_poses_pub_
Publisher for the trajectory pose sequence.
static std_msgs::ColorRGBA toColorMsg(double a, double r, double g, double b)
Helper function to generate a color message from single values.
Config class for the teb_local_planner and its components.
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information...
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.
double & x()
Access the x-coordinate the pose.
geometry_msgs::TransformStamped t
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.
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
void publishRobotFootprintModel(const PoseSE2 ¤t_pose, const BaseRobotFootprintModel &robot_model, const std::string &ns="RobotFootprintModel", const std_msgs::ColorRGBA &color=toColorMsg(0.5, 0.0, 0.8, 0.0))
Publish the visualization of the robot model.
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
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).
void publishObstacles(const ObstContainer &obstacles) const
Publish obstacle positions to the ros topic ../../teb_markers.
struct teb_local_planner::TebConfig::HomotopyClasses hcp
Implements a 2D point obstacle.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
void publishGlobalPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan) const
Publish a given global plan to the ros topic ../../global_plan.
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)
void publishLocalPlanAndPoses(const TimedElasticBand &teb) const
Publish Timed_Elastic_Band related stuff (local plan, pose sequence).
ros::Publisher global_plan_pub_
Publisher for the global plan.
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
void publishInfeasibleRobotPose(const PoseSE2 ¤t_pose, const BaseRobotFootprintModel &robot_model)
Publish the robot footprints related to infeasible poses.
ros::Publisher local_plan_pub_
Publisher for the local plan.
ViaPointContainer via_points
int sizePoses() const
Get the length of the internal pose sequence.
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)