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 
59 {
60 public:
61 
66  {
67  }
68 
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 
102  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const {}
103 
104 
109  virtual double getInscribedRadius() = 0;
110 
111 
112 
113 public:
114  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
115 };
116 
117 
122 
123 
124 
134 {
135 public:
136 
141 
145  virtual ~PointRobotFootprint() {}
146 
153  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
154  {
155  return obstacle->getMinimumDistance(current_pose.position());
156  }
157 
165  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
166  {
167  return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t);
168  }
169 
174  virtual double getInscribedRadius() {return 0.0;}
175 
176 };
177 
178 
184 {
185 public:
186 
191  CircularRobotFootprint(double radius) : radius_(radius) { }
192 
197 
202  void setRadius(double radius) {radius_ = radius;}
203 
210  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
211  {
212  return obstacle->getMinimumDistance(current_pose.position()) - radius_;
213  }
214 
222  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
223  {
224  return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t) - radius_;
225  }
226 
235  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
236  {
237  markers.resize(1);
238  visualization_msgs::Marker& marker = markers.back();
239  marker.type = visualization_msgs::Marker::CYLINDER;
240  current_pose.toPoseMsg(marker.pose);
241  marker.scale.x = marker.scale.y = 2*radius_; // scale = diameter
242  marker.scale.z = 0.05;
243  marker.color.a = 0.5;
244  marker.color.r = 0.0;
245  marker.color.g = 0.8;
246  marker.color.b = 0.0;
247  }
248 
253  virtual double getInscribedRadius() {return radius_;}
254 
255 private:
256 
257  double radius_;
258 };
259 
260 
266 {
267 public:
268 
276  TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
277  : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { }
278 
283 
291  void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
292  {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;}
293 
300  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
301  {
302  Eigen::Vector2d dir = current_pose.orientationUnitVec();
303  double dist_front = obstacle->getMinimumDistance(current_pose.position() + front_offset_*dir) - front_radius_;
304  double dist_rear = obstacle->getMinimumDistance(current_pose.position() - rear_offset_*dir) - rear_radius_;
305  return std::min(dist_front, dist_rear);
306  }
307 
315  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
316  {
317  Eigen::Vector2d dir = current_pose.orientationUnitVec();
318  double dist_front = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() + front_offset_*dir, t) - front_radius_;
319  double dist_rear = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() - rear_offset_*dir, t) - rear_radius_;
320  return std::min(dist_front, dist_rear);
321  }
322 
331  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
332  {
333  std_msgs::ColorRGBA color;
334  color.a = 0.5;
335  color.r = 0.0;
336  color.g = 0.8;
337  color.b = 0.0;
338 
339  Eigen::Vector2d dir = current_pose.orientationUnitVec();
340  if (front_radius_>0)
341  {
342  markers.push_back(visualization_msgs::Marker());
343  visualization_msgs::Marker& marker1 = markers.front();
344  marker1.type = visualization_msgs::Marker::CYLINDER;
345  current_pose.toPoseMsg(marker1.pose);
346  marker1.pose.position.x += front_offset_*dir.x();
347  marker1.pose.position.y += front_offset_*dir.y();
348  marker1.scale.x = marker1.scale.y = 2*front_radius_; // scale = diameter
349 // marker1.scale.z = 0.05;
350  marker1.color = color;
351 
352  }
353  if (rear_radius_>0)
354  {
355  markers.push_back(visualization_msgs::Marker());
356  visualization_msgs::Marker& marker2 = markers.back();
357  marker2.type = visualization_msgs::Marker::CYLINDER;
358  current_pose.toPoseMsg(marker2.pose);
359  marker2.pose.position.x -= rear_offset_*dir.x();
360  marker2.pose.position.y -= rear_offset_*dir.y();
361  marker2.scale.x = marker2.scale.y = 2*rear_radius_; // scale = diameter
362 // marker2.scale.z = 0.05;
363  marker2.color = color;
364  }
365  }
366 
371  virtual double getInscribedRadius()
372  {
373  double min_longitudinal = std::min(rear_offset_ + rear_radius_, front_offset_ + front_radius_);
374  double min_lateral = std::min(rear_radius_, front_radius_);
375  return std::min(min_longitudinal, min_lateral);
376  }
377 
378 private:
379 
382  double rear_offset_;
383  double rear_radius_;
384 
385 };
386 
387 
388 
394 {
395 public:
396 
402  LineRobotFootprint(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
403  {
404  setLine(line_start, line_end);
405  }
406 
412  LineRobotFootprint(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
413  {
414  setLine(line_start, line_end);
415  }
416 
420  virtual ~LineRobotFootprint() { }
421 
426  void setLine(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
427  {
428  line_start_.x() = line_start.x;
429  line_start_.y() = line_start.y;
430  line_end_.x() = line_end.x;
431  line_end_.y() = line_end.y;
432  }
433 
438  void setLine(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
439  {
440  line_start_ = line_start;
441  line_end_ = line_end;
442  }
443 
450  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
451  {
452  Eigen::Vector2d line_start_world;
453  Eigen::Vector2d line_end_world;
454  transformToWorld(current_pose, line_start_world, line_end_world);
455  return obstacle->getMinimumDistance(line_start_world, line_end_world);
456  }
457 
465  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
466  {
467  Eigen::Vector2d line_start_world;
468  Eigen::Vector2d line_end_world;
469  transformToWorld(current_pose, line_start_world, line_end_world);
470  return obstacle->getMinimumSpatioTemporalDistance(line_start_world, line_end_world, t);
471  }
472 
481  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
482  {
483  std_msgs::ColorRGBA color;
484  color.a = 0.5;
485  color.r = 0.0;
486  color.g = 0.8;
487  color.b = 0.0;
488 
489  markers.push_back(visualization_msgs::Marker());
490  visualization_msgs::Marker& marker = markers.front();
491  marker.type = visualization_msgs::Marker::LINE_STRIP;
492  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
493 
494  // line
495  geometry_msgs::Point line_start_world;
496  line_start_world.x = line_start_.x();
497  line_start_world.y = line_start_.y();
498  line_start_world.z = 0;
499  marker.points.push_back(line_start_world);
500 
501  geometry_msgs::Point line_end_world;
502  line_end_world.x = line_end_.x();
503  line_end_world.y = line_end_.y();
504  line_end_world.z = 0;
505  marker.points.push_back(line_end_world);
506 
507  marker.scale.x = 0.05;
508  marker.color = color;
509  }
510 
515  virtual double getInscribedRadius()
516  {
517  return 0.0; // lateral distance = 0.0
518  }
519 
520 private:
521 
528  void transformToWorld(const PoseSE2& current_pose, Eigen::Vector2d& line_start_world, Eigen::Vector2d& line_end_world) const
529  {
530  double cos_th = std::cos(current_pose.theta());
531  double sin_th = std::sin(current_pose.theta());
532  line_start_world.x() = current_pose.x() + cos_th * line_start_.x() - sin_th * line_start_.y();
533  line_start_world.y() = current_pose.y() + sin_th * line_start_.x() + cos_th * line_start_.y();
534  line_end_world.x() = current_pose.x() + cos_th * line_end_.x() - sin_th * line_end_.y();
535  line_end_world.y() = current_pose.y() + sin_th * line_end_.x() + cos_th * line_end_.y();
536  }
537 
538  Eigen::Vector2d line_start_;
539  Eigen::Vector2d line_end_;
540 
541 public:
542  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
543 
544 };
545 
546 
547 
553 {
554 public:
555 
556 
557 
562  PolygonRobotFootprint(const Point2dContainer& vertices) : vertices_(vertices) { }
563 
568 
573  void setVertices(const Point2dContainer& vertices) {vertices_ = vertices;}
574 
581  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
582  {
583  Point2dContainer polygon_world(vertices_.size());
584  transformToWorld(current_pose, polygon_world);
585  return obstacle->getMinimumDistance(polygon_world);
586  }
587 
595  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
596  {
597  Point2dContainer polygon_world(vertices_.size());
598  transformToWorld(current_pose, polygon_world);
599  return obstacle->getMinimumSpatioTemporalDistance(polygon_world, t);
600  }
601 
610  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers ) const
611  {
612  if (vertices_.empty())
613  return;
614 
615  std_msgs::ColorRGBA color;
616  color.a = 0.5;
617  color.r = 0.0;
618  color.g = 0.8;
619  color.b = 0.0;
620 
621  markers.push_back(visualization_msgs::Marker());
622  visualization_msgs::Marker& marker = markers.front();
623  marker.type = visualization_msgs::Marker::LINE_STRIP;
624  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
625 
626  for (std::size_t i = 0; i < vertices_.size(); ++i)
627  {
628  geometry_msgs::Point point;
629  point.x = vertices_[i].x();
630  point.y = vertices_[i].y();
631  point.z = 0;
632  marker.points.push_back(point);
633  }
634  // add first point again in order to close the polygon
635  geometry_msgs::Point point;
636  point.x = vertices_.front().x();
637  point.y = vertices_.front().y();
638  point.z = 0;
639  marker.points.push_back(point);
640 
641  marker.scale.x = 0.025;
642  marker.color = color;
643 
644  }
645 
650  virtual double getInscribedRadius()
651  {
652  double min_dist = std::numeric_limits<double>::max();
653  Eigen::Vector2d center(0.0, 0.0);
654 
655  if (vertices_.size() <= 2)
656  return 0.0;
657 
658  for (int i = 0; i < (int)vertices_.size() - 1; ++i)
659  {
660  // compute distance from the robot center point to the first vertex
661  double vertex_dist = vertices_[i].norm();
662  double edge_dist = distance_point_to_segment_2d(center, vertices_[i], vertices_[i+1]);
663  min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
664  }
665 
666  // we also need to check the last vertex and the first vertex
667  double vertex_dist = vertices_.back().norm();
668  double edge_dist = distance_point_to_segment_2d(center, vertices_.back(), vertices_.front());
669  return std::min(min_dist, std::min(vertex_dist, edge_dist));
670  }
671 
672 private:
673 
679  void transformToWorld(const PoseSE2& current_pose, Point2dContainer& polygon_world) const
680  {
681  double cos_th = std::cos(current_pose.theta());
682  double sin_th = std::sin(current_pose.theta());
683  for (std::size_t i=0; i<vertices_.size(); ++i)
684  {
685  polygon_world[i].x() = current_pose.x() + cos_th * vertices_[i].x() - sin_th * vertices_[i].y();
686  polygon_world[i].y() = current_pose.y() + sin_th * vertices_[i].x() + cos_th * vertices_[i].y();
687  }
688  }
689 
691 
692 };
693 
694 
695 
696 
697 
698 } // namespace teb_local_planner
699 
700 #endif /* ROBOT_FOOTPRINT_MODEL_H */
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
LineRobotFootprint(const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
Default constructor of the abstract obstacle class.
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...
virtual ~LineRobotFootprint()
Virtual destructor.
BaseRobotFootprintModel()
Default constructor of the abstract obstacle class.
Eigen::Vector2d & position()
Access the 2D position part.
Definition: pose_se2.h:145
virtual double getInscribedRadius()=0
Compute the inscribed radius of the footprint model.
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
Visualize the robot using a markers.
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...
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
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...
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
Visualize the robot using a markers.
Abstract class that defines the interface for robot footprint/contour models.
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
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...
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
void setLine(const geometry_msgs::Point &line_start, const geometry_msgs::Point &line_end)
Set vertices of the contour/footprint.
double & x()
Access the x-coordinate the pose.
Definition: pose_se2.h:158
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > Point2dContainer
Abbrev. for a container storing 2d points.
Class that defines the a robot of circular shape.
Eigen::Vector2d orientationUnitVec() const
Return the unit vector of the current orientation.
Definition: pose_se2.h:215
virtual ~PointRobotFootprint()
Virtual destructor.
CircularRobotFootprint(double radius)
Default constructor of the abstract obstacle class.
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...
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
LineRobotFootprint(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end)
Default constructor of the abstract obstacle class (Eigen Version)
void transformToWorld(const PoseSE2 &current_pose, Point2dContainer &polygon_world) const
Transforms a polygon to the world frame manually.
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
virtual ~CircularRobotFootprint()
Virtual destructor.
Class that approximates the robot with line segment (zero-width)
virtual double getMinimumDistance(const Eigen::Vector2d &position) const =0
Get the minimum euclidean distance to the obstacle (point as reference)
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.
void toPoseMsg(geometry_msgs::Pose &pose) const
Convert PoseSE2 to a geometry_msgs::Pose.
Definition: pose_se2.h:203
Class that approximates the robot with a closed polygon.
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
virtual double getInscribedRadius()
Compute the inscribed radius of the footprint model.
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
boost::shared_ptr< const BaseRobotFootprintModel > RobotFootprintModelConstPtr
Abbrev. for shared obstacle const pointers.
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
PointRobotFootprint()
Default constructor of the abstract obstacle class.
virtual ~TwoCirclesRobotFootprint()
Virtual destructor.
PolygonRobotFootprint(const Point2dContainer &vertices)
Default constructor of the abstract obstacle class.
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...
void setVertices(const Point2dContainer &vertices)
Set vertices of the contour/footprint.
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
Visualize the robot using a markers.
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const
Calculate the distance between the robot and an obstacle.
void setLine(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end)
Set vertices of the contour/footprint (Eigen version)
virtual ~BaseRobotFootprintModel()
Virtual destructor.
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
void setRadius(double radius)
Set radius of the circular robot.
Class that approximates the robot with two shifted circles.
virtual ~PolygonRobotFootprint()
Virtual destructor.
TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
Default constructor of the abstract obstacle class.
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
Visualize the robot using a markers.
virtual void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers) const
Visualize the robot using a markers.
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...
Abstract class that defines the interface for modelling obstacles.
Definition: obstacles.h:67
void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
Set parameters of the contour/footprint.
virtual double calculateDistance(const PoseSE2 &current_pose, const Obstacle *obstacle) const =0
Calculate the distance between the robot and an obstacle.
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.


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