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 
50 TebVisualization::TebVisualization(ros::NodeHandle& nh, const TebConfig& cfg) : initialized_(false)
51 {
52  initialize(nh, cfg);
53 }
54 
55 void TebVisualization::initialize(ros::NodeHandle& nh, const TebConfig& cfg)
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);
118 }
119 
120 
121 
122 void TebVisualization::publishRobotFootprintModel(const PoseSE2& current_pose, const BaseRobotFootprintModel& robot_model,
123  const std::string& ns, 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 = 0;
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 
147 void TebVisualization::publishRobotFootprint(const PoseSE2& current_pose, const std::vector<geometry_msgs::Point>& footprint,
148  const std::string& ns, const std_msgs::ColorRGBA &color)
149 {
150  if ( printErrorWhenNotInitialized() || footprint.empty() )
151  return;
152 
153  visualization_msgs::Marker vertex_marker;
154  vertex_marker.header.frame_id = cfg_->map_frame;
155  vertex_marker.header.stamp = ros::Time::now();
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;
161  vertex_marker.lifetime = ros::Duration(2.0);
162  vertex_marker.points = footprint;
163  vertex_marker.points.push_back(footprint.front()); // close the polygon
164  current_pose.toPoseMsg(vertex_marker.pose);
165  teb_marker_pub_.publish(vertex_marker);
166 }
167 
168 void TebVisualization::publishInfeasibleRobotPose(const PoseSE2& infeasible_pose,
169  const BaseRobotFootprintModel& robot_model,
170  const std::vector<geometry_msgs::Point>& footprint)
171 {
172  publishRobotFootprintModel(infeasible_pose, robot_model, "InfeasibleRobotPose/model", toColorMsg(0.5, 0.8, 0.0, 0.0));
173  publishRobotFootprint(infeasible_pose, footprint, "InfeasibleRobotPose/footprint", toColorMsg(0.5, 0.9, 0.7, 0.0));
174 }
175 
176 void TebVisualization::publishObstacles(const ObstContainer& obstacles, double scale) const
177 {
178  if ( obstacles.empty() || printErrorWhenNotInitialized() )
179  return;
180 
181  // Visualize point obstacles
182  {
183  visualization_msgs::Marker marker;
184  marker.header.frame_id = cfg_->map_frame;
185  marker.header.stamp = ros::Time::now();
186  marker.ns = "PointObstacles";
187  marker.id = 0;
188  marker.type = visualization_msgs::Marker::POINTS;
189  marker.action = visualization_msgs::Marker::ADD;
190  marker.lifetime = ros::Duration(2.0);
191 
192  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
193  {
194  boost::shared_ptr<PointObstacle> pobst = boost::dynamic_pointer_cast<PointObstacle>(*obst);
195  if (!pobst)
196  continue;
197 
199  {
200  geometry_msgs::Point point;
201  point.x = pobst->x();
202  point.y = pobst->y();
203  point.z = 0;
204  marker.points.push_back(point);
205  }
206  else // Spatiotemporally point obstacles become a line
207  {
208  marker.type = visualization_msgs::Marker::LINE_LIST;
209  geometry_msgs::Point start;
210  start.x = pobst->x();
211  start.y = pobst->y();
212  start.z = 0;
213  marker.points.push_back(start);
214 
215  geometry_msgs::Point end;
216  double t = 20;
217  Eigen::Vector2d pred;
218  pobst->predictCentroidConstantVelocity(t, pred);
219  end.x = pred[0];
220  end.y = pred[1];
222  marker.points.push_back(end);
223  }
224  }
225 
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;
232 
233  teb_marker_pub_.publish( marker );
234  }
235 
236  // Visualize circular obstacles
237  {
238  std::size_t idx = 0;
239  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
240  {
241  boost::shared_ptr<CircularObstacle> pobst = boost::dynamic_pointer_cast<CircularObstacle>(*obst);
242  if (!pobst)
243  continue;
244 
245  visualization_msgs::Marker marker;
246  marker.header.frame_id = cfg_->map_frame;
247  marker.header.stamp = ros::Time::now();
248  marker.ns = "CircularObstacles";
249  marker.id = idx++;
250  marker.type = visualization_msgs::Marker::SPHERE_LIST;
251  marker.action = visualization_msgs::Marker::ADD;
252  marker.lifetime = ros::Duration(2.0);
253  geometry_msgs::Point point;
254  point.x = pobst->x();
255  point.y = pobst->y();
256  point.z = 0;
257  marker.points.push_back(point);
258 
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;
265 
266  teb_marker_pub_.publish( marker );
267  }
268  }
269 
270  // Visualize line obstacles
271  {
272  std::size_t idx = 0;
273  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
274  {
275  boost::shared_ptr<LineObstacle> pobst = boost::dynamic_pointer_cast<LineObstacle>(*obst);
276  if (!pobst)
277  continue;
278 
279  visualization_msgs::Marker marker;
280  marker.header.frame_id = cfg_->map_frame;
281  marker.header.stamp = ros::Time::now();
282  marker.ns = "LineObstacles";
283  marker.id = idx++;
284  marker.type = visualization_msgs::Marker::LINE_STRIP;
285  marker.action = visualization_msgs::Marker::ADD;
286  marker.lifetime = ros::Duration(2.0);
287  geometry_msgs::Point start;
288  start.x = pobst->start().x();
289  start.y = pobst->start().y();
290  start.z = 0;
291  marker.points.push_back(start);
292  geometry_msgs::Point end;
293  end.x = pobst->end().x();
294  end.y = pobst->end().y();
295  end.z = 0;
296  marker.points.push_back(end);
297 
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;
304 
305  teb_marker_pub_.publish( marker );
306  }
307  }
308 
309 
310  // Visualize polygon obstacles
311  {
312  std::size_t idx = 0;
313  for (ObstContainer::const_iterator obst = obstacles.begin(); obst != obstacles.end(); ++obst)
314  {
315  boost::shared_ptr<PolygonObstacle> pobst = boost::dynamic_pointer_cast<PolygonObstacle>(*obst);
316  if (!pobst)
317  continue;
318 
319  visualization_msgs::Marker marker;
320  marker.header.frame_id = cfg_->map_frame;
321  marker.header.stamp = ros::Time::now();
322  marker.ns = "PolyObstacles";
323  marker.id = idx++;
324  marker.type = visualization_msgs::Marker::LINE_STRIP;
325  marker.action = visualization_msgs::Marker::ADD;
326  marker.lifetime = ros::Duration(2.0);
327 
328  for (Point2dContainer::const_iterator vertex = pobst->vertices().begin(); vertex != pobst->vertices().end(); ++vertex)
329  {
330  geometry_msgs::Point point;
331  point.x = vertex->x();
332  point.y = vertex->y();
333  point.z = 0;
334  marker.points.push_back(point);
335  }
336 
337  // Also add last point to close the polygon
338  // but only if polygon has more than 2 points (it is not a line)
339  if (pobst->vertices().size() > 2)
340  {
341  geometry_msgs::Point point;
342  point.x = pobst->vertices().front().x();
343  point.y = pobst->vertices().front().y();
344  point.z = 0;
345  marker.points.push_back(point);
346  }
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;
353 
354  teb_marker_pub_.publish( marker );
355  }
356  }
357 }
358 
359 
360 void TebVisualization::publishViaPoints(const std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >& via_points, const std::string& ns) const
361 {
362  if ( via_points.empty() || printErrorWhenNotInitialized() )
363  return;
364 
365  visualization_msgs::Marker marker;
366  marker.header.frame_id = cfg_->map_frame;
367  marker.header.stamp = ros::Time::now();
368  marker.ns = ns;
369  marker.id = 0;
370  marker.type = visualization_msgs::Marker::POINTS;
371  marker.action = visualization_msgs::Marker::ADD;
372  marker.lifetime = ros::Duration(2.0);
373 
374  for (std::size_t i=0; i < via_points.size(); ++i)
375  {
376  geometry_msgs::Point point;
377  point.x = via_points[i].x();
378  point.y = via_points[i].y();
379  point.z = 0;
380  marker.points.push_back(point);
381  }
382 
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;
389 
390  teb_marker_pub_.publish( marker );
391 }
392 
393 void TebVisualization::publishTebContainer(const TebOptPlannerContainer& teb_planner, const std::string& ns)
394 {
396  return;
397 
398  visualization_msgs::Marker marker;
399  marker.header.frame_id = cfg_->map_frame;
400  marker.header.stamp = ros::Time::now();
401  marker.ns = ns;
402  marker.id = 0;
403  marker.type = visualization_msgs::Marker::LINE_LIST;
404  marker.action = visualization_msgs::Marker::ADD;
405 
406  // Iterate through teb pose sequence
407  for( TebOptPlannerContainer::const_iterator it_teb = teb_planner.begin(); it_teb != teb_planner.end(); ++it_teb )
408  {
409  // iterate single poses
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); // since we are interested in line segments, reduce end iterator by one.
414  double time = 0;
415 
416  while (it_pose != it_pose_end)
417  {
418  geometry_msgs::Point point_start;
419  point_start.x = (*it_pose)->x();
420  point_start.y = (*it_pose)->y();
421  point_start.z = cfg_->hcp.visualize_with_time_as_z_axis_scale*time;
422  marker.points.push_back(point_start);
423 
424  time += (*it_timediff)->dt();
425 
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);
431  ++it_pose;
432  ++it_timediff;
433  }
434  }
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;
440 
441  teb_marker_pub_.publish( marker );
442 }
443 
445  unsigned int selected_trajectory_idx, const ObstContainer& obstacles)
446 {
447  FeedbackMsg msg;
448  msg.header.stamp = ros::Time::now();
449  msg.header.frame_id = cfg_->map_frame;
450  msg.selected_trajectory_idx = selected_trajectory_idx;
451 
452 
453  msg.trajectories.resize(teb_planners.size());
454 
455  // Iterate through teb pose sequence
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 )
458  {
459  msg.trajectories[idx_traj].header = msg.header;
460  it_teb->get()->getFullTrajectory(msg.trajectories[idx_traj].trajectory);
461  }
462 
463  // add obstacles
464  msg.obstacles_msg.obstacles.resize(obstacles.size());
465  for (std::size_t i=0; i<obstacles.size(); ++i)
466  {
467  msg.obstacles_msg.header = msg.header;
468 
469  // copy polygon
470  msg.obstacles_msg.obstacles[i].header = msg.header;
471  obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
472 
473  // copy id
474  msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet
475 
476  // orientation
477  //msg.obstacles_msg.obstacles[i].orientation =; // TODO
478 
479  // copy velocities
480  obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
481  }
482 
483  feedback_pub_.publish(msg);
484 }
485 
486 void TebVisualization::publishFeedbackMessage(const TebOptimalPlanner& teb_planner, const ObstContainer& obstacles)
487 {
488  FeedbackMsg msg;
489  msg.header.stamp = ros::Time::now();
490  msg.header.frame_id = cfg_->map_frame;
491  msg.selected_trajectory_idx = 0;
492 
493  msg.trajectories.resize(1);
494  msg.trajectories.front().header = msg.header;
495  teb_planner.getFullTrajectory(msg.trajectories.front().trajectory);
496 
497  // add obstacles
498  msg.obstacles_msg.obstacles.resize(obstacles.size());
499  for (std::size_t i=0; i<obstacles.size(); ++i)
500  {
501  msg.obstacles_msg.header = msg.header;
502 
503  // copy polygon
504  msg.obstacles_msg.obstacles[i].header = msg.header;
505  obstacles[i]->toPolygonMsg(msg.obstacles_msg.obstacles[i].polygon);
506 
507  // copy id
508  msg.obstacles_msg.obstacles[i].id = i; // TODO: we do not have any id stored yet
509 
510  // orientation
511  //msg.obstacles_msg.obstacles[i].orientation =; // TODO
512 
513  // copy velocities
514  obstacles[i]->toTwistWithCovarianceMsg(msg.obstacles_msg.obstacles[i].velocities);
515  }
516 
517  feedback_pub_.publish(msg);
518 }
519 
520 std_msgs::ColorRGBA TebVisualization::toColorMsg(double a, double r, double g, double b)
521 {
522  std_msgs::ColorRGBA color;
523  color.a = a;
524  color.r = r;
525  color.g = g;
526  color.b = b;
527  return color;
528 }
529 
531 {
532  if (!initialized_)
533  {
534  ROS_ERROR("TebVisualization class not initialized. You must call initialize or an appropriate constructor");
535  return true;
536  }
537  return false;
538 }
539 
540 } // namespace teb_local_planner
teb_local_planner::TimedElasticBand::Pose
PoseSE2 & Pose(int index)
Access the pose at pos index of the pose sequence.
Definition: timed_elastic_band.h:192
teb_local_planner::PoseSE2::x
double & x()
Access the x-coordinate the pose.
Definition: pose_se2.h:194
boost::shared_ptr
via_points
ViaPointContainer via_points
Definition: test_optim_node.cpp:55
teb_local_planner::PoseSE2::toPoseMsg
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
Definition: pose_se2.h:239
teb_local_planner::PoseSE2::y
double & y()
Access the y-coordinate the pose.
Definition: pose_se2.h:206
teb_local_planner::TimedElasticBand
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information.
Definition: timed_elastic_band.h:122
teb_local_planner::TebVisualization::publishTebContainer
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).
Definition: visualization.cpp:429
teb_local_planner::TebVisualization::publishGlobalPlan
void publishGlobalPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan) const
Publish a given global plan to the ros topic ../../global_plan.
Definition: visualization.cpp:111
teb_local_planner::TebVisualization::teb_marker_pub_
ros::Publisher teb_marker_pub_
Publisher for visualization markers.
Definition: visualization.h:298
export_to_svg.FeedbackMsg
FeedbackMsg
Definition: export_to_svg.py:107
teb_local_planner::TebVisualization::publishInfeasibleRobotPose
void publishInfeasibleRobotPose(const PoseSE2 &infeasible_pose, const BaseRobotFootprintModel &robot_model, const std::vector< geometry_msgs::Point > &footprint)
Publish the robot footprint model and the actual robot footprint at an infeasible pose.
Definition: visualization.cpp:204
teb_local_planner::TebConfig::hcp
struct teb_local_planner::TebConfig::HomotopyClasses hcp
teb_local_planner::BaseRobotFootprintModel
Abstract class that defines the interface for robot footprint/contour models.
Definition: robot_footprint_model.h:94
teb_local_planner::BaseRobotFootprintModel::visualizeRobot
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.
Definition: robot_footprint_model.h:139
teb_local_planner::TebConfig::HomotopyClasses::visualize_with_time_as_z_axis_scale
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:210
teb_local_planner::TebVisualization::feedback_pub_
ros::Publisher feedback_pub_
Publisher for the feedback message for analysis and debug purposes.
Definition: visualization.h:299
teb_local_planner::TebVisualization::printErrorWhenNotInitialized
bool printErrorWhenNotInitialized() const
Small helper function that checks if initialize() has been called and prints an error message if not.
Definition: visualization.cpp:566
teb_local_planner::TebVisualization::toColorMsg
static std_msgs::ColorRGBA toColorMsg(double a, double r, double g, double b)
Helper function to generate a color message from single values.
Definition: visualization.cpp:556
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
export_to_svg.point
list point
Definition: export_to_svg.py:223
teb_local_planner::TimedElasticBand::getSumOfTimeDiffsUpToIdx
double getSumOfTimeDiffsUpToIdx(int index) const
Calculate the estimated transition time up to the pose denoted by index.
Definition: timed_elastic_band.cpp:336
teb_local_planner::TebVisualization::publishFeedbackMessage
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)
Definition: visualization.cpp:480
teb_local_planner::TebVisualization::initialize
void initialize(ros::NodeHandle &nh, const TebConfig &cfg)
Initializes the class and registers topics.
Definition: visualization.cpp:91
teb_local_planner::PoseSE2::theta
double & theta()
Access the orientation part (yaw angle) of the pose.
Definition: pose_se2.h:218
teb_local_planner::ObstContainer
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:333
teb_local_planner::TebVisualization::publishObstacles
void publishObstacles(const ObstContainer &obstacles, double scale=0.1) const
Publish obstacle positions to the ros topic ../../teb_markers.
Definition: visualization.cpp:212
teb_local_planner::TebVisualization::local_plan_pub_
ros::Publisher local_plan_pub_
Publisher for the local plan.
Definition: visualization.h:296
ROS_WARN
#define ROS_WARN(...)
teb_local_planner::TimedElasticBand::sizePoses
int sizePoses() const
Get the length of the internal pose sequence.
Definition: timed_elastic_band.h:635
teb_local_planner::TebVisualization::TebVisualization
TebVisualization()
Default constructor.
Definition: visualization.cpp:82
teb_local_planner::TebVisualization::teb_poses_pub_
ros::Publisher teb_poses_pub_
Publisher for the trajectory pose sequence.
Definition: visualization.h:297
start
ROSCPP_DECL void start()
teb_local_planner::PoseSE2
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:93
teb_local_planner::TebVisualization::global_plan_pub_
ros::Publisher global_plan_pub_
Publisher for the global plan.
Definition: visualization.h:295
teb_local_planner::TebConfig::map_frame
std::string map_frame
Global planning frame.
Definition: teb_config.h:67
teb_local_planner::TebVisualization::publishRobotFootprintModel
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.
Definition: visualization.cpp:158
initialize
ROSCONSOLE_DECL void initialize()
ROS_ERROR
#define ROS_ERROR(...)
teb_local_planner::TebVisualization::publishViaPoints
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.
Definition: visualization.cpp:396
teb_local_planner::TebVisualization::publishLocalPlanAndPoses
void publishLocalPlanAndPoses(const TimedElasticBand &teb) const
Publish Timed_Elastic_Band related stuff (local plan, pose sequence).
Definition: visualization.cpp:124
teb_local_planner::TebVisualization::publishRobotFootprint
void publishRobotFootprint(const PoseSE2 &current_pose, const std::vector< geometry_msgs::Point > &footprint, const std::string &ns, const std_msgs::ColorRGBA &color)
Definition: visualization.cpp:183
teb_local_planner::TebVisualization::initialized_
bool initialized_
Keeps track about the correct initialization of this class.
Definition: visualization.h:303
teb_local_planner::TebOptPlannerContainer
std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer
Abbrev. for containers storing multiple teb optimal planners.
Definition: optimal_planner.h:738
optimal_planner.h
teb_local_planner::TebVisualization::publishLocalPlan
void publishLocalPlan(const std::vector< geometry_msgs::PoseStamped > &local_plan) const
Publish a given local plan to the ros topic ../../local_plan.
Definition: visualization.cpp:117
teb_local_planner::TebVisualization::cfg_
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Definition: visualization.h:301
tf::createQuaternionMsgFromYaw
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
teb_local_planner
Definition: distance_calculations.h:46
base_local_planner::publishPlan
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
ros::Duration
visualization.h
t
geometry_msgs::TransformStamped t
ros::NodeHandle
ros::Time::now
static Time now()


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15