visualization.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
41 #include <teb_local_planner/FeedbackMsg.h>
42 
43 namespace teb_local_planner
44 {
45 
46 TebVisualization::TebVisualization() : initialized_(false)
47 {
48 }
49 
51 {
52  initialize(nh, cfg);
53 }
54 
56 {
57  if (initialized_)
58  ROS_WARN("TebVisualization already initialized. Reinitalizing...");
59 
60  // set config
61  cfg_ = &cfg;
62 
63  // register topics
64  global_plan_pub_ = nh.advertise<nav_msgs::Path>("global_plan", 1);
65  local_plan_pub_ = nh.advertise<nav_msgs::Path>("local_plan",1);
66  teb_poses_pub_ = nh.advertise<geometry_msgs::PoseArray>("teb_poses", 100);
67  teb_marker_pub_ = nh.advertise<visualization_msgs::Marker>("teb_markers", 1000);
68  feedback_pub_ = nh.advertise<teb_local_planner::FeedbackMsg>("teb_feedback", 10);
69 
70  initialized_ = true;
71 }
72 
73 
74 
75 void TebVisualization::publishGlobalPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan) const
76 {
77  if ( printErrorWhenNotInitialized() ) return;
79 }
80 
81 void TebVisualization::publishLocalPlan(const std::vector<geometry_msgs::PoseStamped>& local_plan) const
82 {
84  return;
86 }
87 
89 {
91  return;
92 
93  // create path msg
94  nav_msgs::Path teb_path;
95  teb_path.header.frame_id = cfg_->map_frame;
96  teb_path.header.stamp = ros::Time::now();
97 
98  // create pose_array (along trajectory)
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;
102 
103  // fill path msgs with teb configurations
104  for (int i=0; i < teb.sizePoses(); i++)
105  {
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();
112  pose.pose.orientation = tf::createQuaternionMsgFromYaw(teb.Pose(i).theta());
113  teb_path.poses.push_back(pose);
114  teb_poses.poses.push_back(pose.pose);
115  }
116  local_plan_pub_.publish(teb_path);
117  teb_poses_pub_.publish(teb_poses);
118 }
119 
120 
121 
122 void TebVisualization::publishRobotFootprintModel(const PoseSE2& current_pose, const BaseRobotFootprintModel& robot_model, const std::string& ns,
123  const std_msgs::ColorRGBA &color)
124 {
126  return;
127 
128  std::vector<visualization_msgs::Marker> markers;
129  robot_model.visualizeRobot(current_pose, markers, color);
130  if (markers.empty())
131  return;
132 
133  int idx = 1000000; // avoid overshadowing by obstacles
134  for (std::vector<visualization_msgs::Marker>::iterator marker_it = markers.begin(); marker_it != markers.end(); ++marker_it, ++idx)
135  {
136  marker_it->header.frame_id = cfg_->map_frame;
137  marker_it->header.stamp = ros::Time::now();
138  marker_it->action = visualization_msgs::Marker::ADD;
139  marker_it->ns = ns;
140  marker_it->id = idx;
141  marker_it->lifetime = ros::Duration(2.0);
142  teb_marker_pub_.publish(*marker_it);
143  }
144 
145 }
146 
148 {
149  publishRobotFootprintModel(current_pose, robot_model, "InfeasibleRobotPoses", toColorMsg(0.5, 0.8, 0.0, 0.0));
150 }
151 
152 
154 {
155  if ( obstacles.empty() || printErrorWhenNotInitialized() )
156  return;
157 
158  // Visualize point obstacles
159  {
160  visualization_msgs::Marker marker;
161  marker.header.frame_id = cfg_->map_frame;
162  marker.header.stamp = ros::Time::now();
163  marker.ns = "PointObstacles";
164  marker.id = 0;
165  marker.type = visualization_msgs::Marker::POINTS;
166  marker.action = visualization_msgs::Marker::ADD;
167  marker.lifetime = ros::Duration(2.0);
168 
169  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
170  {
171  boost::shared_ptr<PointObstacle> pobst = boost::dynamic_pointer_cast<PointObstacle>(*obst);
172  if (!pobst)
173  continue;
174 
176  {
177  geometry_msgs::Point point;
178  point.x = pobst->x();
179  point.y = pobst->y();
180  point.z = 0;
181  marker.points.push_back(point);
182  }
183  else // Spatiotemporally point obstacles become a line
184  {
185  marker.type = visualization_msgs::Marker::LINE_LIST;
186  geometry_msgs::Point start;
187  start.x = pobst->x();
188  start.y = pobst->y();
189  start.z = 0;
190  marker.points.push_back(start);
191 
192  geometry_msgs::Point end;
193  double t = 20;
194  Eigen::Vector2d pred;
195  pobst->predictCentroidConstantVelocity(t, pred);
196  end.x = pred[0];
197  end.y = pred[1];
199  marker.points.push_back(end);
200  }
201  }
202 
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;
209 
210  teb_marker_pub_.publish( marker );
211  }
212 
213  // Visualize circular obstacles
214  {
215  std::size_t idx = 0;
216  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
217  {
218  boost::shared_ptr<CircularObstacle> pobst = boost::dynamic_pointer_cast<CircularObstacle>(*obst);
219  if (!pobst)
220  continue;
221 
222  visualization_msgs::Marker marker;
223  marker.header.frame_id = cfg_->map_frame;
224  marker.header.stamp = ros::Time::now();
225  marker.ns = "CircularObstacles";
226  marker.id = idx++;
227  marker.type = visualization_msgs::Marker::SPHERE_LIST;
228  marker.action = visualization_msgs::Marker::ADD;
229  marker.lifetime = ros::Duration(2.0);
230  geometry_msgs::Point point;
231  point.x = pobst->x();
232  point.y = pobst->y();
233  point.z = 0;
234  marker.points.push_back(point);
235 
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;
242 
243  teb_marker_pub_.publish( marker );
244  }
245  }
246 
247  // Visualize line obstacles
248  {
249  std::size_t idx = 0;
250  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
251  {
252  boost::shared_ptr<LineObstacle> pobst = boost::dynamic_pointer_cast<LineObstacle>(*obst);
253  if (!pobst)
254  continue;
255 
256  visualization_msgs::Marker marker;
257  marker.header.frame_id = cfg_->map_frame;
258  marker.header.stamp = ros::Time::now();
259  marker.ns = "LineObstacles";
260  marker.id = idx++;
261  marker.type = visualization_msgs::Marker::LINE_STRIP;
262  marker.action = visualization_msgs::Marker::ADD;
263  marker.lifetime = ros::Duration(2.0);
264  geometry_msgs::Point start;
265  start.x = pobst->start().x();
266  start.y = pobst->start().y();
267  start.z = 0;
268  marker.points.push_back(start);
269  geometry_msgs::Point end;
270  end.x = pobst->end().x();
271  end.y = pobst->end().y();
272  end.z = 0;
273  marker.points.push_back(end);
274 
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;
281 
282  teb_marker_pub_.publish( marker );
283  }
284  }
285 
286 
287  // Visualize polygon obstacles
288  {
289  std::size_t idx = 0;
290  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
291  {
292  boost::shared_ptr<PolygonObstacle> pobst = boost::dynamic_pointer_cast<PolygonObstacle>(*obst);
293  if (!pobst)
294  continue;
295 
296  visualization_msgs::Marker marker;
297  marker.header.frame_id = cfg_->map_frame;
298  marker.header.stamp = ros::Time::now();
299  marker.ns = "PolyObstacles";
300  marker.id = idx++;
301  marker.type = visualization_msgs::Marker::LINE_STRIP;
302  marker.action = visualization_msgs::Marker::ADD;
303  marker.lifetime = ros::Duration(2.0);
304 
305  for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex)
306  {
307  geometry_msgs::Point point;
308  point.x = vertex->x();
309  point.y = vertex->y();
310  point.z = 0;
311  marker.points.push_back(point);
312  }
313 
314  // Also add last point to close the polygon
315  // but only if polygon has more than 2 points (it is not a line)
316  if (pobst->vertices().size() > 2)
317  {
318  geometry_msgs::Point point;
319  point.x = pobst->vertices().front().x();
320  point.y = pobst->vertices().front().y();
321  point.z = 0;
322  marker.points.push_back(point);
323  }
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;
330 
331  teb_marker_pub_.publish( marker );
332  }
333  }
334 }
335 
336 
337 void TebVisualization::publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >& via_points, const std::string& ns) const
338 {
339  if ( via_points.empty() || printErrorWhenNotInitialized() )
340  return;
341 
342  visualization_msgs::Marker marker;
343  marker.header.frame_id = cfg_->map_frame;
344  marker.header.stamp = ros::Time::now();
345  marker.ns = ns;
346  marker.id = 0;
347  marker.type = visualization_msgs::Marker::POINTS;
348  marker.action = visualization_msgs::Marker::ADD;
349  marker.lifetime = ros::Duration(2.0);
350 
351  for (std::size_t i=0; i < via_points.size(); ++i)
352  {
353  geometry_msgs::Point point;
354  point.x = via_points[i].x();
355  point.y = via_points[i].y();
356  point.z = 0;
357  marker.points.push_back(point);
358  }
359 
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;
366 
367  teb_marker_pub_.publish( marker );
368 }
369 
370 void TebVisualization::publishTebContainer(const TebOptPlannerContainer& teb_planner, const std::string& ns)
371 {
373  return;
374 
375  visualization_msgs::Marker marker;
376  marker.header.frame_id = cfg_->map_frame;
377  marker.header.stamp = ros::Time::now();
378  marker.ns = ns;
379  marker.id = 0;
380  marker.type = visualization_msgs::Marker::LINE_LIST;
381  marker.action = visualization_msgs::Marker::ADD;
382 
383  // Iterate through teb pose sequence
384  for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb )
385  {
386  // iterate single poses
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); // since we are interested in line segments, reduce end iterator by one.
391  double time = 0;
392 
393  while (it_pose != it_pose_end)
394  {
395  geometry_msgs::Point point_start;
396  point_start.x = (*it_pose)->x();
397  point_start.y = (*it_pose)->y();
398  point_start.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time;
399  marker.points.push_back(point_start);
400 
401  time += (*it_timediff)->dt();
402 
403  geometry_msgs::Point point_end;
404  point_end.x = (*boost::next(it_pose))->x();
405  point_end.y = (*boost::next(it_pose))->y();
406  point_end.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time;
407  marker.points.push_back(point_end);
408  ++it_pose;
409  ++it_timediff;
410  }
411  }
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;
417 
418  teb_marker_pub_.publish( marker );
419 }
420 
422  unsigned int selected_trajectory_idx, const ObstContainer& obstacles)
423 {
424  FeedbackMsg msg;
425  msg.header.stamp = ros::Time::now();
426  msg.header.frame_id = cfg_->map_frame;
427  msg.selected_trajectory_idx = selected_trajectory_idx;
428 
429 
430  msg.trajectories.resize(teb_planners.size());
431 
432  // Iterate through teb pose sequence
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 )
435  {
436  msg.trajectories[idx_traj].header = msg.header;
437  it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory);
438  }
439 
440  // add obstacles
441  msg.obstacles_msg.obstacles.resize(obstacles.size());
442  for (std::size_t i=0; i<obstacles.size(); ++i)
443  {
444  msg.obstacles_msg.header = msg.header;
445 
446  // copy polygon
447  msg.obstacles_msg.obstacles[i].header = msg.header;
448  obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
449 
450  // copy id
451  msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet
452 
453  // orientation
454  //msg.obstacles_msg.obstacles[i].orientation =; // TODO
455 
456  // copy velocities
457  obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
458  }
459 
460  feedback_pub_.publish(msg);
461 }
462 
464 {
465  FeedbackMsg msg;
466  msg.header.stamp = ros::Time::now();
467  msg.header.frame_id = cfg_->map_frame;
468  msg.selected_trajectory_idx = 0;
469 
470  msg.trajectories.resize(1);
471  msg.trajectories.front().header = msg.header;
472  teb_planner.getFullTrajectory(msg.trajectories.front().trajectory);
473 
474  // add obstacles
475  msg.obstacles_msg.obstacles.resize(obstacles.size());
476  for (std::size_t i=0; i<obstacles.size(); ++i)
477  {
478  msg.obstacles_msg.header = msg.header;
479 
480  // copy polygon
481  msg.obstacles_msg.obstacles[i].header = msg.header;
482  obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
483 
484  // copy id
485  msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet
486 
487  // orientation
488  //msg.obstacles_msg.obstacles[i].orientation =; // TODO
489 
490  // copy velocities
491  obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
492  }
493 
494  feedback_pub_.publish(msg);
495 }
496 
497 std_msgs::ColorRGBA TebVisualization::toColorMsg(double a, double r, double g, double b)
498 {
499  std_msgs::ColorRGBA color;
500  color.a = a;
501  color.r = r;
502  color.g = g;
503  color.b = b;
504  return color;
505 }
506 
508 {
509  if (!initialized_)
510  {
511  ROS_ERROR("TebVisualization class not initialized. You must call initialize or an appropriate constructor");
512  return true;
513  }
514  return false;
515 }
516 
517 } // namespace teb_local_planner
Implements a 2D circular obstacle (point obstacle plus radius)
Definition: obstacles.h:447
std::string map_frame
Global planning frame.
Definition: teb_config.h:66
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.
ROSCPP_DECL void start()
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.
Definition: teb_config.h:61
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information...
Abstract class that defines the interface for robot footprint/contour models.
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.
Definition: pose_se2.h:158
#define ROS_WARN(...)
geometry_msgs::TransformStamped t
Implements a polygon obstacle with an arbitrary number of vertices.
Definition: obstacles.h:898
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...
Definition: teb_config.h:206
Implements a 2D line obstacle.
Definition: obstacles.h:597
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
void publishRobotFootprintModel(const PoseSE2 &current_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.
Definition: obstacles.h:305
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:297
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.
Definition: pose_se2.h:170
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:57
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: pose_se2.h:182
TebVisualization()
Default constructor.
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers, const std_msgs::ColorRGBA &color) const
Visualize the robot using a markers.
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 &current_pose, const BaseRobotFootprintModel &robot_model)
Publish the robot footprints related to infeasible poses.
static Time now()
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)
#define ROS_ERROR(...)


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 1 2022 02:26:31