robot_footprint_model.h
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 
39 
40 #ifndef ROBOT_FOOTPRINT_MODEL_H
41 #define ROBOT_FOOTPRINT_MODEL_H
42 
45 #include <visualization_msgs/Marker.h>
46 
47 namespace teb_local_planner
48 {
49 
58 class BaseRobotFootprintModel
59 {
60 public:
61 
66  {
67  }
68 
72  virtual ~BaseRobotFootprintModel()
73  {
74  }
75 
76 
83  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const = 0;
84 
92  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const = 0;
93 
103  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const {}
104 
105 
110  virtual double getInscribedRadius() = 0;
111 
112 
113 
114 public:
115  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
116 };
117 
118 
123 
124 
125 
134 class PointRobotFootprint : public BaseRobotFootprintModel
135 {
136 public:
137 
142 
147  PointRobotFootprint(const double min_obstacle_dist) : min_obstacle_dist_(min_obstacle_dist) {}
148 
152  virtual ~PointRobotFootprint() {}
153 
160  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
161  {
162  return obstacle->getMinimumDistance(current_pose.position());
163  }
164 
172  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
173  {
174  return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t);
175  }
176 
181  virtual double getInscribedRadius() {return 0.0;}
182 
192  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
193  {
194  // point footprint
195  markers.push_back(visualization_msgs::Marker());
196  visualization_msgs::Marker& marker = markers.back();
197  marker.type = visualization_msgs::Marker::POINTS;
198  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
199  marker.points.push_back(geometry_msgs::Point());
200  marker.scale.x = 0.025;
201  marker.color = color;
202 
203  if (min_obstacle_dist_ <= 0)
204  {
205  return;
206  }
207 
208  // footprint with min_obstacle_dist
209  markers.push_back(visualization_msgs::Marker());
210  visualization_msgs::Marker& marker2 = markers.back();
211  marker2.type = visualization_msgs::Marker::LINE_STRIP;
212  marker2.scale.x = 0.025;
213  marker2.color = color;
214  current_pose.toPoseMsg(marker2.pose); // all points are transformed into the robot frame!
215 
216  const double n = 9;
217  const double r = min_obstacle_dist_;
218  for (double theta = 0; theta <= 2 * M_PI; theta += M_PI / n)
219  {
220  geometry_msgs::Point pt;
221  pt.x = r * cos(theta);
222  pt.y = r * sin(theta);
223  marker2.points.push_back(pt);
224  }
225  }
226 
227 private:
228  const double min_obstacle_dist_ = 0.0;
229 };
230 
231 
237 {
238 public:
239 
244  CircularRobotFootprint(double radius) : radius_(radius) { }
245 
249  virtual ~CircularRobotFootprint() { }
250 
255  void setRadius(double radius) {radius_ = radius;}
256 
263  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
264  {
265  return obstacle->getMinimumDistance(current_pose.position()) - radius_;
266  }
267 
275  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
276  {
277  return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t) - radius_;
278  }
279 
289  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
290  {
291  markers.resize(1);
292  visualization_msgs::Marker& marker = markers.back();
293  marker.type = visualization_msgs::Marker::CYLINDER;
294  current_pose.toPoseMsg(marker.pose);
295  marker.scale.x = marker.scale.y = 2*radius_; // scale = diameter
296  marker.scale.z = 0.05;
297  marker.color = color;
298  }
299 
304  virtual double getInscribedRadius() {return radius_;}
305 
306 private:
307 
308  double radius_;
309 };
310 
311 
317 {
318 public:
319 
327  TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
328  : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { }
329 
333  virtual ~TwoCirclesRobotFootprint() { }
334 
342  void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
343  {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;}
344 
351  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
352  {
353  Eigen::Vector2d dir = current_pose.orientationUnitVec();
354  double dist_front = obstacle->getMinimumDistance(current_pose.position() + front_offset_*dir) - front_radius_;
355  double dist_rear = obstacle->getMinimumDistance(current_pose.position() - rear_offset_*dir) - rear_radius_;
356  return std::min(dist_front, dist_rear);
357  }
358 
366  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
367  {
368  Eigen::Vector2d dir = current_pose.orientationUnitVec();
369  double dist_front = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() + front_offset_*dir, t) - front_radius_;
370  double dist_rear = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() - rear_offset_*dir, t) - rear_radius_;
371  return std::min(dist_front, dist_rear);
372  }
373 
383  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
384  {
385  Eigen::Vector2d dir = current_pose.orientationUnitVec();
386  if (front_radius_>0)
387  {
388  markers.push_back(visualization_msgs::Marker());
389  visualization_msgs::Marker& marker1 = markers.back();
390  marker1.type = visualization_msgs::Marker::CYLINDER;
391  current_pose.toPoseMsg(marker1.pose);
392  marker1.pose.position.x += front_offset_*dir.x();
393  marker1.pose.position.y += front_offset_*dir.y();
394  marker1.scale.x = marker1.scale.y = 2*front_radius_; // scale = diameter
395 // marker1.scale.z = 0.05;
396  marker1.color = color;
397 
398  }
399  if (rear_radius_>0)
400  {
401  markers.push_back(visualization_msgs::Marker());
402  visualization_msgs::Marker& marker2 = markers.back();
403  marker2.type = visualization_msgs::Marker::CYLINDER;
404  current_pose.toPoseMsg(marker2.pose);
405  marker2.pose.position.x -= rear_offset_*dir.x();
406  marker2.pose.position.y -= rear_offset_*dir.y();
407  marker2.scale.x = marker2.scale.y = 2*rear_radius_; // scale = diameter
408 // marker2.scale.z = 0.05;
409  marker2.color = color;
410  }
411  }
412 
417  virtual double getInscribedRadius()
418  {
419  double min_longitudinal = std::min(rear_offset_ + rear_radius_, front_offset_ + front_radius_);
420  double min_lateral = std::min(rear_radius_, front_radius_);
421  return std::min(min_longitudinal, min_lateral);
422  }
423 
424 private:
425 
426  double front_offset_;
427  double front_radius_;
428  double rear_offset_;
429  double rear_radius_;
430 
431 };
432 
433 
434 
439 class LineRobotFootprint : public BaseRobotFootprintModel
440 {
441 public:
442 
448  LineRobotFootprint(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
449  {
451  }
452 
458  LineRobotFootprint(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end, const double min_obstacle_dist) : min_obstacle_dist_(min_obstacle_dist)
459  {
461  }
462 
466  virtual ~LineRobotFootprint() { }
467 
472  void setLine(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
473  {
474  line_start_.x() = line_start.x;
476  line_end_.x() = line_end.x;
477  line_end_.y() = line_end.y;
478  }
479 
484  void setLine(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
485  {
488  }
489 
496  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
497  {
498  Eigen::Vector2d line_start_world;
499  Eigen::Vector2d line_end_world;
500  transformToWorld(current_pose, line_start_world, line_end_world);
501  return obstacle->getMinimumDistance(line_start_world, line_end_world);
502  }
503 
511  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
512  {
513  Eigen::Vector2d line_start_world;
514  Eigen::Vector2d line_end_world;
515  transformToWorld(current_pose, line_start_world, line_end_world);
516  return obstacle->getMinimumSpatioTemporalDistance(line_start_world, line_end_world, t);
517  }
518 
528  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
529  {
530  markers.push_back(visualization_msgs::Marker());
531  visualization_msgs::Marker& marker = markers.back();
532  marker.type = visualization_msgs::Marker::LINE_STRIP;
533  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
534 
535  // line
536  geometry_msgs::Point line_start_world;
537  line_start_world.x = line_start_.x();
538  line_start_world.y = line_start_.y();
539  line_start_world.z = 0;
540  marker.points.push_back(line_start_world);
541 
542  geometry_msgs::Point line_end_world;
543  line_end_world.x = line_end_.x();
544  line_end_world.y = line_end_.y();
545  line_end_world.z = 0;
546  marker.points.push_back(line_end_world);
547 
548  marker.scale.x = 0.025;
549  marker.color = color;
550 
551  if (min_obstacle_dist_ <= 0)
552  {
553  return;
554  }
555 
556  // footprint with min_obstacle_dist
557  markers.push_back(visualization_msgs::Marker());
558  visualization_msgs::Marker& marker2 = markers.back();
559  marker2.type = visualization_msgs::Marker::LINE_STRIP;
560  marker2.scale.x = 0.025;
561  marker2.color = color;
562  current_pose.toPoseMsg(marker2.pose); // all points are transformed into the robot frame!
563 
564  const double n = 9;
565  const double r = min_obstacle_dist_;
566  const double ori = atan2(line_end_.y() - line_start_.y(), line_end_.x() - line_start_.x());
567 
568  // first half-circle
569  for (double theta = M_PI_2 + ori; theta <= 3 * M_PI_2 + ori; theta += M_PI / n)
570  {
571  geometry_msgs::Point pt;
572  pt.x = line_start_.x() + r * cos(theta);
573  pt.y = line_start_.y() + r * sin(theta);
574  marker2.points.push_back(pt);
575  }
576 
577  // second half-circle
578  for (double theta = -M_PI_2 + ori; theta <= M_PI_2 + ori; theta += M_PI / n)
579  {
580  geometry_msgs::Point pt;
581  pt.x = line_end_.x() + r * cos(theta);
582  pt.y = line_end_.y() + r * sin(theta);
583  marker2.points.push_back(pt);
584  }
585 
586  // duplicate 1st point to close shape
587  geometry_msgs::Point pt;
588  pt.x = line_start_.x() + r * cos(M_PI_2 + ori);
589  pt.y = line_start_.y() + r * sin(M_PI_2 + ori);
590  marker2.points.push_back(pt);
591  }
592 
597  virtual double getInscribedRadius()
598  {
599  return 0.0; // lateral distance = 0.0
600  }
601 
602 private:
603 
610  void transformToWorld(const PoseSE2& current_pose, Eigen::Vector2d& line_start_world, Eigen::Vector2d& line_end_world) const
611  {
612  double cos_th = std::cos(current_pose.theta());
613  double sin_th = std::sin(current_pose.theta());
614  line_start_world.x() = current_pose.x() + cos_th * line_start_.x() - sin_th * line_start_.y();
615  line_start_world.y() = current_pose.y() + sin_th * line_start_.x() + cos_th * line_start_.y();
616  line_end_world.x() = current_pose.x() + cos_th * line_end_.x() - sin_th * line_end_.y();
617  line_end_world.y() = current_pose.y() + sin_th * line_end_.x() + cos_th * line_end_.y();
618  }
619 
620  Eigen::Vector2d line_start_;
621  Eigen::Vector2d line_end_;
622  const double min_obstacle_dist_ = 0.0;
623 
624 public:
625  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
626 
627 };
628 
629 
630 
635 class PolygonRobotFootprint : public BaseRobotFootprintModel
636 {
637 public:
638 
639 
640 
646 
650  virtual ~PolygonRobotFootprint() { }
651 
657 
664  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
665  {
666  Point2dContainer polygon_world(vertices_.size());
667  transformToWorld(current_pose, polygon_world);
668  return obstacle->getMinimumDistance(polygon_world);
669  }
670 
678  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
679  {
680  Point2dContainer polygon_world(vertices_.size());
681  transformToWorld(current_pose, polygon_world);
682  return obstacle->getMinimumSpatioTemporalDistance(polygon_world, t);
683  }
684 
694  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
695  {
696  if (vertices_.empty())
697  return;
698 
699  markers.push_back(visualization_msgs::Marker());
700  visualization_msgs::Marker& marker = markers.back();
701  marker.type = visualization_msgs::Marker::LINE_STRIP;
702  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
703 
704  for (std::size_t i = 0; i < vertices_.size(); ++i)
705  {
706  geometry_msgs::Point point;
707  point.x = vertices_[i].x();
708  point.y = vertices_[i].y();
709  point.z = 0;
710  marker.points.push_back(point);
711  }
712  // add first point again in order to close the polygon
713  geometry_msgs::Point point;
714  point.x = vertices_.front().x();
715  point.y = vertices_.front().y();
716  point.z = 0;
717  marker.points.push_back(point);
718 
719  marker.scale.x = 0.025;
720  marker.color = color;
721 
722  }
723 
728  virtual double getInscribedRadius()
729  {
730  double min_dist = std::numeric_limits<double>::max();
731  Eigen::Vector2d center(0.0, 0.0);
732 
733  if (vertices_.size() <= 2)
734  return 0.0;
735 
736  for (int i = 0; i < (int)vertices_.size() - 1; ++i)
737  {
738  // compute distance from the robot center point to the first vertex
739  double vertex_dist = vertices_[i].norm();
740  double edge_dist = distance_point_to_segment_2d(center, vertices_[i], vertices_[i+1]);
741  min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
742  }
743 
744  // we also need to check the last vertex and the first vertex
745  double vertex_dist = vertices_.back().norm();
746  double edge_dist = distance_point_to_segment_2d(center, vertices_.back(), vertices_.front());
747  return std::min(min_dist, std::min(vertex_dist, edge_dist));
748  }
749 
750 private:
751 
757  void transformToWorld(const PoseSE2& current_pose, Point2dContainer& polygon_world) const
758  {
759  double cos_th = std::cos(current_pose.theta());
760  double sin_th = std::sin(current_pose.theta());
761  for (std::size_t i=0; i<vertices_.size(); ++i)
762  {
763  polygon_world[i].x() = current_pose.x() + cos_th * vertices_[i].x() - sin_th * vertices_[i].y();
764  polygon_world[i].y() = current_pose.y() + sin_th * vertices_[i].x() + cos_th * vertices_[i].y();
765  }
766  }
767 
769 
770 };
771 
772 
773 
774 
775 
776 } // namespace teb_local_planner
777 
778 #endif /* ROBOT_FOOTPRINT_MODEL_H */
teb_local_planner::PolygonRobotFootprint::PolygonRobotFootprint
PolygonRobotFootprint(const Point2dContainer &vertices)
Default constructor of the abstract obstacle class.
Definition: robot_footprint_model.h:681
teb_local_planner::TwoCirclesRobotFootprint::estimateSpatioTemporalDistance
virtual double estimateSpatioTemporalDistance(const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const
Estimate the distance between the robot and the predicted location of an obstacle at time t.
Definition: robot_footprint_model.h:402
teb_local_planner::PointRobotFootprint::getInscribedRadius
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
Definition: robot_footprint_model.h:217
teb_local_planner::RobotFootprintModelPtr
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
Definition: robot_footprint_model.h:156
teb_local_planner::LineRobotFootprint::LineRobotFootprint
LineRobotFootprint(const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
Default constructor of the abstract obstacle class.
Definition: robot_footprint_model.h:484
teb_local_planner::CircularRobotFootprint::setRadius
void setRadius(double radius)
Set radius of the circular robot.
Definition: robot_footprint_model.h:291
teb_local_planner::PointRobotFootprint::estimateSpatioTemporalDistance
virtual double estimateSpatioTemporalDistance(const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const
Estimate the distance between the robot and the predicted location of an obstacle at time t.
Definition: robot_footprint_model.h:208
boost::shared_ptr< BaseRobotFootprintModel >
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::TwoCirclesRobotFootprint::rear_radius_
double rear_radius_
Definition: robot_footprint_model.h:465
teb_local_planner::TwoCirclesRobotFootprint::TwoCirclesRobotFootprint
TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
Default constructor of the abstract obstacle class.
Definition: robot_footprint_model.h:363
teb_local_planner::Obstacle::getMinimumDistance
virtual double getMinimumDistance(const Eigen::Vector2d &position) const =0
Get the minimum euclidean distance to the obstacle (point as reference)
teb_local_planner::LineRobotFootprint::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:564
teb_local_planner::Point2dContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Definition: distance_calculations.h:86
teb_local_planner::BaseRobotFootprintModel::getInscribedRadius
virtual double getInscribedRadius()=0
Compute the inscribed radius of the footprint model.
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::Obstacle
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:103
teb_local_planner::Obstacle::getMinimumSpatioTemporalDistance
virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const =0
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity mo...
teb_local_planner::PolygonRobotFootprint::transformToWorld
void transformToWorld(const PoseSE2 &current_pose, Point2dContainer &polygon_world) const
Transforms a polygon to the world frame manually.
Definition: robot_footprint_model.h:793
teb_local_planner::CircularRobotFootprint::CircularRobotFootprint
CircularRobotFootprint(double radius)
Default constructor of the abstract obstacle class.
Definition: robot_footprint_model.h:280
teb_local_planner::PointRobotFootprint::PointRobotFootprint
PointRobotFootprint()
Default constructor of the abstract obstacle class.
Definition: robot_footprint_model.h:177
teb_local_planner::PointRobotFootprint::calculateDistance
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
Definition: robot_footprint_model.h:196
teb_local_planner::LineRobotFootprint::setLine
void setLine(const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
Set vertices of the contour/footprint.
Definition: robot_footprint_model.h:508
export_to_svg.line_end
list line_end
Definition: export_to_svg.py:229
teb_local_planner::TwoCirclesRobotFootprint::~TwoCirclesRobotFootprint
virtual ~TwoCirclesRobotFootprint()
Virtual destructor.
Definition: robot_footprint_model.h:369
teb_local_planner::CircularRobotFootprint
Class that defines the a robot of circular shape.
Definition: robot_footprint_model.h:272
export_to_svg.point
list point
Definition: export_to_svg.py:223
teb_local_planner::TwoCirclesRobotFootprint::rear_offset_
double rear_offset_
Definition: robot_footprint_model.h:464
teb_local_planner::PointRobotFootprint::min_obstacle_dist_
const double min_obstacle_dist_
Definition: robot_footprint_model.h:264
obstacles.h
teb_local_planner::PolygonRobotFootprint::calculateDistance
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
Definition: robot_footprint_model.h:700
teb_local_planner::PointRobotFootprint::~PointRobotFootprint
virtual ~PointRobotFootprint()
Virtual destructor.
Definition: robot_footprint_model.h:188
teb_local_planner::distance_point_to_segment_2d
double distance_point_to_segment_2d(const Eigen::Ref< const Eigen::Vector2d > &point, const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end)
Helper function to calculate the distance between a line segment and a point.
Definition: distance_calculations.h:119
teb_local_planner::RobotFootprintModelConstPtr
boost::shared_ptr< const BaseRobotFootprintModel > RobotFootprintModelConstPtr
Abbrev. for shared obstacle const pointers.
Definition: robot_footprint_model.h:158
teb_local_planner::LineRobotFootprint::line_start_
Eigen::Vector2d line_start_
Definition: robot_footprint_model.h:656
teb_local_planner::LineRobotFootprint::estimateSpatioTemporalDistance
virtual double estimateSpatioTemporalDistance(const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const
Estimate the distance between the robot and the predicted location of an obstacle at time t.
Definition: robot_footprint_model.h:547
teb_local_planner::TwoCirclesRobotFootprint::front_radius_
double front_radius_
Definition: robot_footprint_model.h:463
teb_local_planner::CircularRobotFootprint::~CircularRobotFootprint
virtual ~CircularRobotFootprint()
Virtual destructor.
Definition: robot_footprint_model.h:285
teb_local_planner::PoseSE2::position
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:181
teb_local_planner::LineRobotFootprint::~LineRobotFootprint
virtual ~LineRobotFootprint()
Virtual destructor.
Definition: robot_footprint_model.h:502
export_to_svg.vertices
list vertices
Definition: export_to_svg.py:233
teb_local_planner::CircularRobotFootprint::radius_
double radius_
Definition: robot_footprint_model.h:344
teb_local_planner::PointRobotFootprint::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:228
teb_local_planner::TwoCirclesRobotFootprint::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:419
teb_local_planner::TwoCirclesRobotFootprint
Class that approximates the robot with two shifted circles.
Definition: robot_footprint_model.h:352
export_to_svg.line_start
list line_start
Definition: export_to_svg.py:228
teb_local_planner::TwoCirclesRobotFootprint::calculateDistance
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
Definition: robot_footprint_model.h:387
teb_local_planner::PolygonRobotFootprint::setVertices
void setVertices(const Point2dContainer &vertices)
Set vertices of the contour/footprint.
Definition: robot_footprint_model.h:692
teb_local_planner::PolygonRobotFootprint::~PolygonRobotFootprint
virtual ~PolygonRobotFootprint()
Virtual destructor.
Definition: robot_footprint_model.h:686
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::PoseSE2::orientationUnitVec
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:251
teb_local_planner::LineRobotFootprint::line_end_
Eigen::Vector2d line_end_
Definition: robot_footprint_model.h:657
teb_local_planner::PolygonRobotFootprint::getInscribedRadius
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
Definition: robot_footprint_model.h:764
teb_local_planner::PolygonRobotFootprint::vertices_
Point2dContainer vertices_
Definition: robot_footprint_model.h:804
teb_local_planner::BaseRobotFootprintModel::estimateSpatioTemporalDistance
virtual double estimateSpatioTemporalDistance(const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const =0
Estimate the distance between the robot and the predicted location of an obstacle at time t.
teb_local_planner::LineRobotFootprint::calculateDistance
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
Definition: robot_footprint_model.h:532
teb_local_planner::CircularRobotFootprint::calculateDistance
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
Definition: robot_footprint_model.h:299
teb_local_planner::PolygonRobotFootprint::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:730
teb_local_planner::LineRobotFootprint::transformToWorld
void transformToWorld(const PoseSE2 &current_pose, Eigen::Vector2d &line_start_world, Eigen::Vector2d &line_end_world) const
Transforms a line to the world frame manually.
Definition: robot_footprint_model.h:646
teb_local_planner::TwoCirclesRobotFootprint::setParameters
void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
Set parameters of the contour/footprint.
Definition: robot_footprint_model.h:378
teb_local_planner::TwoCirclesRobotFootprint::getInscribedRadius
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
Definition: robot_footprint_model.h:453
teb_local_planner::LineRobotFootprint::getInscribedRadius
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
Definition: robot_footprint_model.h:633
teb_local_planner::CircularRobotFootprint::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:325
teb_local_planner::BaseRobotFootprintModel::calculateDistance
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const =0
Calculate the distance between the robot and an obstacle.
teb_local_planner::TwoCirclesRobotFootprint::front_offset_
double front_offset_
Definition: robot_footprint_model.h:462
teb_local_planner::PolygonRobotFootprint::estimateSpatioTemporalDistance
virtual double estimateSpatioTemporalDistance(const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const
Estimate the distance between the robot and the predicted location of an obstacle at time t.
Definition: robot_footprint_model.h:714
teb_local_planner::BaseRobotFootprintModel::~BaseRobotFootprintModel
virtual ~BaseRobotFootprintModel()
Virtual destructor.
Definition: robot_footprint_model.h:108
pose_se2.h
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::CircularRobotFootprint::getInscribedRadius
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
Definition: robot_footprint_model.h:340
teb_local_planner::BaseRobotFootprintModel::BaseRobotFootprintModel
BaseRobotFootprintModel()
Default constructor of the abstract obstacle class.
Definition: robot_footprint_model.h:101
teb_local_planner::CircularRobotFootprint::estimateSpatioTemporalDistance
virtual double estimateSpatioTemporalDistance(const PoseSE2 &current_pose, const Obstacle *obstacle, double t) const
Estimate the distance between the robot and the predicted location of an obstacle at time t.
Definition: robot_footprint_model.h:311
t
geometry_msgs::TransformStamped t
teb_local_planner::LineRobotFootprint::min_obstacle_dist_
const double min_obstacle_dist_
Definition: robot_footprint_model.h:658


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