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::string& ns,
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;
148 const std::string& ns,
const std_msgs::ColorRGBA &color)
153 visualization_msgs::Marker vertex_marker;
156 vertex_marker.ns = ns;
157 vertex_marker.type = visualization_msgs::Marker::LINE_STRIP;
158 vertex_marker.action = visualization_msgs::Marker::ADD;
159 vertex_marker.color = color;
160 vertex_marker.scale.x = 0.01;
162 vertex_marker.points = footprint;
163 vertex_marker.points.push_back(footprint.front());
164 current_pose.
toPoseMsg(vertex_marker.pose);
170 const std::vector<geometry_msgs::Point>& footprint)
183 visualization_msgs::Marker marker;
186 marker.ns =
"PointObstacles";
188 marker.type = visualization_msgs::Marker::POINTS;
189 marker.action = visualization_msgs::Marker::ADD;
192 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
200 geometry_msgs::Point
point;
201 point.x = pobst->x();
202 point.y = pobst->y();
208 marker.type = visualization_msgs::Marker::LINE_LIST;
209 geometry_msgs::Point
start;
210 start.x = pobst->x();
211 start.y = pobst->y();
213 marker.points.push_back(start);
215 geometry_msgs::Point end;
217 Eigen::Vector2d pred;
218 pobst->predictCentroidConstantVelocity(t, pred);
222 marker.points.push_back(end);
226 marker.scale.x = scale;
227 marker.scale.y = scale;
228 marker.color.a = 1.0;
229 marker.color.r = 1.0;
230 marker.color.g = 0.0;
231 marker.color.b = 0.0;
239 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
245 visualization_msgs::Marker marker;
248 marker.ns =
"CircularObstacles";
250 marker.type = visualization_msgs::Marker::SPHERE_LIST;
251 marker.action = visualization_msgs::Marker::ADD;
253 geometry_msgs::Point
point;
254 point.x = pobst->x();
255 point.y = pobst->y();
257 marker.points.push_back(
point);
259 marker.scale.x = pobst->radius();
260 marker.scale.y = pobst->radius();
261 marker.color.a = 1.0;
262 marker.color.r = 0.0;
263 marker.color.g = 1.0;
264 marker.color.b = 0.0;
273 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
279 visualization_msgs::Marker marker;
282 marker.ns =
"LineObstacles";
284 marker.type = visualization_msgs::Marker::LINE_STRIP;
285 marker.action = visualization_msgs::Marker::ADD;
287 geometry_msgs::Point
start;
288 start.x = pobst->start().x();
289 start.y = pobst->start().y();
291 marker.points.push_back(start);
292 geometry_msgs::Point end;
293 end.x = pobst->end().x();
294 end.y = pobst->end().y();
296 marker.points.push_back(end);
298 marker.scale.x = scale;
299 marker.scale.y = scale;
300 marker.color.a = 1.0;
301 marker.color.r = 0.0;
302 marker.color.g = 1.0;
303 marker.color.b = 0.0;
313 for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
319 visualization_msgs::Marker marker;
322 marker.ns =
"PolyObstacles";
324 marker.type = visualization_msgs::Marker::LINE_STRIP;
325 marker.action = visualization_msgs::Marker::ADD;
328 for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex)
330 geometry_msgs::Point
point;
331 point.x = vertex->x();
332 point.y = vertex->y();
334 marker.points.push_back(
point);
339 if (pobst->vertices().size() > 2)
341 geometry_msgs::Point
point;
342 point.x = pobst->vertices().front().x();
343 point.y = pobst->vertices().front().y();
345 marker.points.push_back(
point);
347 marker.scale.x = scale;
348 marker.scale.y = scale;
349 marker.color.a = 1.0;
350 marker.color.r = 1.0;
351 marker.color.g = 0.0;
352 marker.color.b = 0.0;
365 visualization_msgs::Marker marker;
370 marker.type = visualization_msgs::Marker::POINTS;
371 marker.action = visualization_msgs::Marker::ADD;
374 for (std::size_t i=0; i <
via_points.size(); ++i)
376 geometry_msgs::Point
point;
380 marker.points.push_back(
point);
383 marker.scale.x = 0.1;
384 marker.scale.y = 0.1;
385 marker.color.a = 1.0;
386 marker.color.r = 0.0;
387 marker.color.g = 0.0;
388 marker.color.b = 1.0;
398 visualization_msgs::Marker marker;
403 marker.type = visualization_msgs::Marker::LINE_LIST;
404 marker.action = visualization_msgs::Marker::ADD;
407 for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb )
410 PoseSequence::const_iterator it_pose = it_teb->get()->teb().poses().begin();
411 TimeDiffSequence::const_iterator it_timediff = it_teb->get()->teb().timediffs().begin();
412 PoseSequence::const_iterator it_pose_end = it_teb->get()->teb().poses().end();
413 std::advance(it_pose_end, -1);
416 while (it_pose != it_pose_end)
418 geometry_msgs::Point point_start;
419 point_start.x = (*it_pose)->x();
420 point_start.y = (*it_pose)->y();
422 marker.points.push_back(point_start);
424 time += (*it_timediff)->dt();
426 geometry_msgs::Point point_end;
427 point_end.x = (*boost::next(it_pose))->x();
428 point_end.y = (*boost::next(it_pose))->y();
430 marker.points.push_back(point_end);
435 marker.scale.x = 0.01;
436 marker.color.a = 1.0;
437 marker.color.r = 0.5;
438 marker.color.g = 1.0;
439 marker.color.b = 0.0;
445 unsigned int selected_trajectory_idx,
const ObstContainer& obstacles)
450 msg.selected_trajectory_idx = selected_trajectory_idx;
453 msg.trajectories.resize(teb_planners.size());
456 std::size_t idx_traj = 0;
457 for( TebOptPlannerContainer::const_iterator it_teb = teb_planners.begin(); it_teb != teb_planners.end(); ++it_teb, ++idx_traj )
459 msg.trajectories[idx_traj].header = msg.header;
460 it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory);
464 msg.obstacles_msg.obstacles.resize(obstacles.size());
465 for (std::size_t i=0; i<obstacles.size(); ++i)
467 msg.obstacles_msg.header = msg.header;
470 msg.obstacles_msg.obstacles[i].header = msg.header;
471 obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
474 msg.obstacles_msg.obstacles[i].id = i;
480 obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
491 msg.selected_trajectory_idx = 0;
493 msg.trajectories.resize(1);
494 msg.trajectories.front().header = msg.header;
495 teb_planner.getFullTrajectory(msg.trajectories.front().trajectory);
498 msg.obstacles_msg.obstacles.resize(obstacles.size());
499 for (std::size_t i=0; i<obstacles.size(); ++i)
501 msg.obstacles_msg.header = msg.header;
504 msg.obstacles_msg.obstacles[i].header = msg.header;
505 obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
508 msg.obstacles_msg.obstacles[i].id = i;
514 obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
522 std_msgs::ColorRGBA color;
534 ROS_ERROR(
"TebVisualization class not initialized. You must call initialize or an appropriate constructor");