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 {
125  return;
126 
127  std::vector<visualization_msgs::Marker> markers;
128  robot_model.visualizeRobot(current_pose, markers);
129  if (markers.empty())
130  return;
131 
132  int idx = 0;
133  for (std::vector<visualization_msgs::Marker>::iterator marker_it = markers.begin(); marker_it != markers.end(); ++marker_it, ++idx)
134  {
135  marker_it->header.frame_id = cfg_->map_frame;
136  marker_it->header.stamp = ros::Time::now();
137  marker_it->action = visualization_msgs::Marker::ADD;
138  marker_it->ns = ns;
139  marker_it->id = idx;
140  marker_it->lifetime = ros::Duration(2.0);
141  teb_marker_pub_.publish(*marker_it);
142  }
143 
144 }
145 
146 
148 {
149  if ( obstacles.empty() || printErrorWhenNotInitialized() )
150  return;
151 
152  // Visualize point obstacles
153  {
154  visualization_msgs::Marker marker;
155  marker.header.frame_id = cfg_->map_frame;
156  marker.header.stamp = ros::Time::now();
157  marker.ns = "PointObstacles";
158  marker.id = 0;
159  marker.type = visualization_msgs::Marker::POINTS;
160  marker.action = visualization_msgs::Marker::ADD;
161  marker.lifetime = ros::Duration(2.0);
162 
163  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
164  {
165  boost::shared_ptr<PointObstacle> pobst = boost::dynamic_pointer_cast<PointObstacle>(*obst);
166  if (!pobst)
167  continue;
168 
170  {
171  geometry_msgs::Point point;
172  point.x = pobst->x();
173  point.y = pobst->y();
174  point.z = 0;
175  marker.points.push_back(point);
176  }
177  else // Spatiotemporally point obstacles become a line
178  {
179  marker.type = visualization_msgs::Marker::LINE_LIST;
180  geometry_msgs::Point start;
181  start.x = pobst->x();
182  start.y = pobst->y();
183  start.z = 0;
184  marker.points.push_back(start);
185 
186  geometry_msgs::Point end;
187  double t = 20;
188  Eigen::Vector2d pred;
189  pobst->predictCentroidConstantVelocity(t, pred);
190  end.x = pred[0];
191  end.y = pred[1];
193  marker.points.push_back(end);
194  }
195  }
196 
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;
203 
204  teb_marker_pub_.publish( marker );
205  }
206 
207  // Visualize line obstacles
208  {
209  std::size_t idx = 0;
210  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
211  {
212  boost::shared_ptr<LineObstacle> pobst = boost::dynamic_pointer_cast<LineObstacle>(*obst);
213  if (!pobst)
214  continue;
215 
216  visualization_msgs::Marker marker;
217  marker.header.frame_id = cfg_->map_frame;
218  marker.header.stamp = ros::Time::now();
219  marker.ns = "LineObstacles";
220  marker.id = idx++;
221  marker.type = visualization_msgs::Marker::LINE_STRIP;
222  marker.action = visualization_msgs::Marker::ADD;
223  marker.lifetime = ros::Duration(2.0);
224  geometry_msgs::Point start;
225  start.x = pobst->start().x();
226  start.y = pobst->start().y();
227  start.z = 0;
228  marker.points.push_back(start);
229  geometry_msgs::Point end;
230  end.x = pobst->end().x();
231  end.y = pobst->end().y();
232  end.z = 0;
233  marker.points.push_back(end);
234 
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;
241 
242  teb_marker_pub_.publish( marker );
243  }
244  }
245 
246 
247  // Visualize polygon 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<PolygonObstacle> pobst = boost::dynamic_pointer_cast<PolygonObstacle>(*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 = "PolyObstacles";
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 
265  for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex)
266  {
267  geometry_msgs::Point point;
268  point.x = vertex->x();
269  point.y = vertex->y();
270  point.z = 0;
271  marker.points.push_back(point);
272  }
273 
274  // Also add last point to close the polygon
275  // but only if polygon has more than 2 points (it is not a line)
276  if (pobst->vertices().size() > 2)
277  {
278  geometry_msgs::Point point;
279  point.x = pobst->vertices().front().x();
280  point.y = pobst->vertices().front().y();
281  point.z = 0;
282  marker.points.push_back(point);
283  }
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;
290 
291  teb_marker_pub_.publish( marker );
292  }
293  }
294 }
295 
296 
297 void TebVisualization::publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >& via_points, const std::string& ns) const
298 {
299  if ( via_points.empty() || printErrorWhenNotInitialized() )
300  return;
301 
302  visualization_msgs::Marker marker;
303  marker.header.frame_id = cfg_->map_frame;
304  marker.header.stamp = ros::Time::now();
305  marker.ns = ns;
306  marker.id = 0;
307  marker.type = visualization_msgs::Marker::POINTS;
308  marker.action = visualization_msgs::Marker::ADD;
309  marker.lifetime = ros::Duration(2.0);
310 
311  for (std::size_t i=0; i < via_points.size(); ++i)
312  {
313  geometry_msgs::Point point;
314  point.x = via_points[i].x();
315  point.y = via_points[i].y();
316  point.z = 0;
317  marker.points.push_back(point);
318  }
319 
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;
326 
327  teb_marker_pub_.publish( marker );
328 }
329 
330 void TebVisualization::publishTebContainer(const TebOptPlannerContainer& teb_planner, const std::string& ns)
331 {
333  return;
334 
335  visualization_msgs::Marker marker;
336  marker.header.frame_id = cfg_->map_frame;
337  marker.header.stamp = ros::Time::now();
338  marker.ns = ns;
339  marker.id = 0;
340  marker.type = visualization_msgs::Marker::LINE_LIST;
341  marker.action = visualization_msgs::Marker::ADD;
342 
343  // Iterate through teb pose sequence
344  for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb )
345  {
346  // iterate single poses
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); // since we are interested in line segments, reduce end iterator by one.
351  double time = 0;
352 
353  while (it_pose != it_pose_end)
354  {
355  geometry_msgs::Point point_start;
356  point_start.x = (*it_pose)->x();
357  point_start.y = (*it_pose)->y();
358  point_start.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time;
359  marker.points.push_back(point_start);
360 
361  time += (*it_timediff)->dt();
362 
363  geometry_msgs::Point point_end;
364  point_end.x = (*boost::next(it_pose))->x();
365  point_end.y = (*boost::next(it_pose))->y();
366  point_end.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time;
367  marker.points.push_back(point_end);
368  ++it_pose;
369  ++it_timediff;
370  }
371  }
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;
377 
378  teb_marker_pub_.publish( marker );
379 }
380 
382  unsigned int selected_trajectory_idx, const ObstContainer& obstacles)
383 {
384  FeedbackMsg msg;
385  msg.header.stamp = ros::Time::now();
386  msg.header.frame_id = cfg_->map_frame;
387  msg.selected_trajectory_idx = selected_trajectory_idx;
388 
389 
390  msg.trajectories.resize(teb_planners.size());
391 
392  // Iterate through teb pose sequence
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 )
395  {
396  msg.trajectories[idx_traj].header = msg.header;
397  it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory);
398  }
399 
400  // add obstacles
401  msg.obstacles_msg.obstacles.resize(obstacles.size());
402  for (std::size_t i=0; i<obstacles.size(); ++i)
403  {
404  msg.obstacles_msg.header = msg.header;
405 
406  // copy polygon
407  msg.obstacles_msg.obstacles[i].header = msg.header;
408  obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
409 
410  // copy id
411  msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet
412 
413  // orientation
414  //msg.obstacles_msg.obstacles[i].orientation =; // TODO
415 
416  // copy velocities
417  obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
418  }
419 
420  feedback_pub_.publish(msg);
421 }
422 
424 {
425  FeedbackMsg msg;
426  msg.header.stamp = ros::Time::now();
427  msg.header.frame_id = cfg_->map_frame;
428  msg.selected_trajectory_idx = 0;
429 
430  msg.trajectories.resize(1);
431  msg.trajectories.front().header = msg.header;
432  teb_planner.getFullTrajectory(msg.trajectories.front().trajectory);
433 
434  // add obstacles
435  msg.obstacles_msg.obstacles.resize(obstacles.size());
436  for (std::size_t i=0; i<obstacles.size(); ++i)
437  {
438  msg.obstacles_msg.header = msg.header;
439 
440  // copy polygon
441  msg.obstacles_msg.obstacles[i].header = msg.header;
442  obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
443 
444  // copy id
445  msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet
446 
447  // orientation
448  //msg.obstacles_msg.obstacles[i].orientation =; // TODO
449 
450  // copy velocities
451  obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
452  }
453 
454  feedback_pub_.publish(msg);
455 }
456 
458 {
459  if (!initialized_)
460  {
461  ROS_ERROR("TebVisualization class not initialized. You must call initialize or an appropriate constructor");
462  return true;
463  }
464  return false;
465 }
466 
467 } // namespace teb_local_planner
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.
Definition: teb_config.h:66
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.
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.
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.
Definition: pose_se2.h:158
TFSIMD_FORCE_INLINE const tfScalar & y() const
#define ROS_WARN(...)
Implements a polygon obstacle with an arbitrary number of vertices.
Definition: obstacles.h:748
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:188
Implements a 2D line obstacle.
Definition: obstacles.h:597
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.
Definition: obstacles.h:305
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:297
void publishRobotFootprintModel(const PoseSE2 &current_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.
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)
ros::Publisher global_plan_pub_
Publisher for the global plan.
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
static Time now()
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.
#define ROS_ERROR(...)
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
Visualize the robot using a markers.


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 5 2019 19:25:10