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 
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 
135 {
136 public:
137 
142 
146  virtual ~PointRobotFootprint() {}
147 
154  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
155  {
156  return obstacle->getMinimumDistance(current_pose.position());
157  }
158 
166  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
167  {
168  return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t);
169  }
170 
175  virtual double getInscribedRadius() {return 0.0;}
176 
177 };
178 
179 
185 {
186 public:
187 
192  CircularRobotFootprint(double radius) : radius_(radius) { }
193 
198 
203  void setRadius(double radius) {radius_ = radius;}
204 
211  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
212  {
213  return obstacle->getMinimumDistance(current_pose.position()) - radius_;
214  }
215 
223  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
224  {
225  return obstacle->getMinimumSpatioTemporalDistance(current_pose.position(), t) - radius_;
226  }
227 
237  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
238  {
239  markers.resize(1);
240  visualization_msgs::Marker& marker = markers.back();
241  marker.type = visualization_msgs::Marker::CYLINDER;
242  current_pose.toPoseMsg(marker.pose);
243  marker.scale.x = marker.scale.y = 2*radius_; // scale = diameter
244  marker.scale.z = 0.05;
245  marker.color = color;
246  }
247 
252  virtual double getInscribedRadius() {return radius_;}
253 
254 private:
255 
256  double radius_;
257 };
258 
259 
265 {
266 public:
267 
275  TwoCirclesRobotFootprint(double front_offset, double front_radius, double rear_offset, double rear_radius)
276  : front_offset_(front_offset), front_radius_(front_radius), rear_offset_(rear_offset), rear_radius_(rear_radius) { }
277 
282 
290  void setParameters(double front_offset, double front_radius, double rear_offset, double rear_radius)
291  {front_offset_=front_offset; front_radius_=front_radius; rear_offset_=rear_offset; rear_radius_=rear_radius;}
292 
299  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
300  {
301  Eigen::Vector2d dir = current_pose.orientationUnitVec();
302  double dist_front = obstacle->getMinimumDistance(current_pose.position() + front_offset_*dir) - front_radius_;
303  double dist_rear = obstacle->getMinimumDistance(current_pose.position() - rear_offset_*dir) - rear_radius_;
304  return std::min(dist_front, dist_rear);
305  }
306 
314  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
315  {
316  Eigen::Vector2d dir = current_pose.orientationUnitVec();
317  double dist_front = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() + front_offset_*dir, t) - front_radius_;
318  double dist_rear = obstacle->getMinimumSpatioTemporalDistance(current_pose.position() - rear_offset_*dir, t) - rear_radius_;
319  return std::min(dist_front, dist_rear);
320  }
321 
331  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
332  {
333  Eigen::Vector2d dir = current_pose.orientationUnitVec();
334  if (front_radius_>0)
335  {
336  markers.push_back(visualization_msgs::Marker());
337  visualization_msgs::Marker& marker1 = markers.back();
338  marker1.type = visualization_msgs::Marker::CYLINDER;
339  current_pose.toPoseMsg(marker1.pose);
340  marker1.pose.position.x += front_offset_*dir.x();
341  marker1.pose.position.y += front_offset_*dir.y();
342  marker1.scale.x = marker1.scale.y = 2*front_radius_; // scale = diameter
343 // marker1.scale.z = 0.05;
344  marker1.color = color;
345 
346  }
347  if (rear_radius_>0)
348  {
349  markers.push_back(visualization_msgs::Marker());
350  visualization_msgs::Marker& marker2 = markers.back();
351  marker2.type = visualization_msgs::Marker::CYLINDER;
352  current_pose.toPoseMsg(marker2.pose);
353  marker2.pose.position.x -= rear_offset_*dir.x();
354  marker2.pose.position.y -= rear_offset_*dir.y();
355  marker2.scale.x = marker2.scale.y = 2*rear_radius_; // scale = diameter
356 // marker2.scale.z = 0.05;
357  marker2.color = color;
358  }
359  }
360 
365  virtual double getInscribedRadius()
366  {
367  double min_longitudinal = std::min(rear_offset_ + rear_radius_, front_offset_ + front_radius_);
368  double min_lateral = std::min(rear_radius_, front_radius_);
369  return std::min(min_longitudinal, min_lateral);
370  }
371 
372 private:
373 
376  double rear_offset_;
377  double rear_radius_;
378 
379 };
380 
381 
382 
388 {
389 public:
390 
396  LineRobotFootprint(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
397  {
398  setLine(line_start, line_end);
399  }
400 
406  LineRobotFootprint(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
407  {
408  setLine(line_start, line_end);
409  }
410 
414  virtual ~LineRobotFootprint() { }
415 
420  void setLine(const geometry_msgs::Point& line_start, const geometry_msgs::Point& line_end)
421  {
422  line_start_.x() = line_start.x;
423  line_start_.y() = line_start.y;
424  line_end_.x() = line_end.x;
425  line_end_.y() = line_end.y;
426  }
427 
432  void setLine(const Eigen::Vector2d& line_start, const Eigen::Vector2d& line_end)
433  {
434  line_start_ = line_start;
435  line_end_ = line_end;
436  }
437 
444  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
445  {
446  Eigen::Vector2d line_start_world;
447  Eigen::Vector2d line_end_world;
448  transformToWorld(current_pose, line_start_world, line_end_world);
449  return obstacle->getMinimumDistance(line_start_world, line_end_world);
450  }
451 
459  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
460  {
461  Eigen::Vector2d line_start_world;
462  Eigen::Vector2d line_end_world;
463  transformToWorld(current_pose, line_start_world, line_end_world);
464  return obstacle->getMinimumSpatioTemporalDistance(line_start_world, line_end_world, t);
465  }
466 
476  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
477  {
478  markers.push_back(visualization_msgs::Marker());
479  visualization_msgs::Marker& marker = markers.back();
480  marker.type = visualization_msgs::Marker::LINE_STRIP;
481  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
482 
483  // line
484  geometry_msgs::Point line_start_world;
485  line_start_world.x = line_start_.x();
486  line_start_world.y = line_start_.y();
487  line_start_world.z = 0;
488  marker.points.push_back(line_start_world);
489 
490  geometry_msgs::Point line_end_world;
491  line_end_world.x = line_end_.x();
492  line_end_world.y = line_end_.y();
493  line_end_world.z = 0;
494  marker.points.push_back(line_end_world);
495 
496  marker.scale.x = 0.05;
497  marker.color = color;
498  }
499 
504  virtual double getInscribedRadius()
505  {
506  return 0.0; // lateral distance = 0.0
507  }
508 
509 private:
510 
517  void transformToWorld(const PoseSE2& current_pose, Eigen::Vector2d& line_start_world, Eigen::Vector2d& line_end_world) const
518  {
519  double cos_th = std::cos(current_pose.theta());
520  double sin_th = std::sin(current_pose.theta());
521  line_start_world.x() = current_pose.x() + cos_th * line_start_.x() - sin_th * line_start_.y();
522  line_start_world.y() = current_pose.y() + sin_th * line_start_.x() + cos_th * line_start_.y();
523  line_end_world.x() = current_pose.x() + cos_th * line_end_.x() - sin_th * line_end_.y();
524  line_end_world.y() = current_pose.y() + sin_th * line_end_.x() + cos_th * line_end_.y();
525  }
526 
527  Eigen::Vector2d line_start_;
528  Eigen::Vector2d line_end_;
529 
530 public:
531  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
532 
533 };
534 
535 
536 
542 {
543 public:
544 
545 
546 
551  PolygonRobotFootprint(const Point2dContainer& vertices) : vertices_(vertices) { }
552 
557 
562  void setVertices(const Point2dContainer& vertices) {vertices_ = vertices;}
563 
570  virtual double calculateDistance(const PoseSE2& current_pose, const Obstacle* obstacle) const
571  {
572  Point2dContainer polygon_world(vertices_.size());
573  transformToWorld(current_pose, polygon_world);
574  return obstacle->getMinimumDistance(polygon_world);
575  }
576 
584  virtual double estimateSpatioTemporalDistance(const PoseSE2& current_pose, const Obstacle* obstacle, double t) const
585  {
586  Point2dContainer polygon_world(vertices_.size());
587  transformToWorld(current_pose, polygon_world);
588  return obstacle->getMinimumSpatioTemporalDistance(polygon_world, t);
589  }
590 
600  virtual void visualizeRobot(const PoseSE2& current_pose, std::vector<visualization_msgs::Marker>& markers, const std_msgs::ColorRGBA& color) const
601  {
602  if (vertices_.empty())
603  return;
604 
605  markers.push_back(visualization_msgs::Marker());
606  visualization_msgs::Marker& marker = markers.back();
607  marker.type = visualization_msgs::Marker::LINE_STRIP;
608  current_pose.toPoseMsg(marker.pose); // all points are transformed into the robot frame!
609 
610  for (std::size_t i = 0; i < vertices_.size(); ++i)
611  {
612  geometry_msgs::Point point;
613  point.x = vertices_[i].x();
614  point.y = vertices_[i].y();
615  point.z = 0;
616  marker.points.push_back(point);
617  }
618  // add first point again in order to close the polygon
619  geometry_msgs::Point point;
620  point.x = vertices_.front().x();
621  point.y = vertices_.front().y();
622  point.z = 0;
623  marker.points.push_back(point);
624 
625  marker.scale.x = 0.025;
626  marker.color = color;
627 
628  }
629 
634  virtual double getInscribedRadius()
635  {
636  double min_dist = std::numeric_limits<double>::max();
637  Eigen::Vector2d center(0.0, 0.0);
638 
639  if (vertices_.size() <= 2)
640  return 0.0;
641 
642  for (int i = 0; i < (int)vertices_.size() - 1; ++i)
643  {
644  // compute distance from the robot center point to the first vertex
645  double vertex_dist = vertices_[i].norm();
646  double edge_dist = distance_point_to_segment_2d(center, vertices_[i], vertices_[i+1]);
647  min_dist = std::min(min_dist, std::min(vertex_dist, edge_dist));
648  }
649 
650  // we also need to check the last vertex and the first vertex
651  double vertex_dist = vertices_.back().norm();
652  double edge_dist = distance_point_to_segment_2d(center, vertices_.back(), vertices_.front());
653  return std::min(min_dist, std::min(vertex_dist, edge_dist));
654  }
655 
656 private:
657 
663  void transformToWorld(const PoseSE2& current_pose, Point2dContainer& polygon_world) const
664  {
665  double cos_th = std::cos(current_pose.theta());
666  double sin_th = std::sin(current_pose.theta());
667  for (std::size_t i=0; i<vertices_.size(); ++i)
668  {
669  polygon_world[i].x() = current_pose.x() + cos_th * vertices_[i].x() - sin_th * vertices_[i].y();
670  polygon_world[i].y() = current_pose.y() + sin_th * vertices_[i].x() + cos_th * vertices_[i].y();
671  }
672  }
673 
675 
676 };
677 
678 
679 
680 
681 
682 } // namespace teb_local_planner
683 
684 #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 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 std_msgs::ColorRGBA &color) const
Visualize the robot using a markers.
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.
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.
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 void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers, const std_msgs::ColorRGBA &color) const
Visualize the robot using a markers.
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 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 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 void visualizeRobot(const PoseSE2 &current_pose, std::vector< visualization_msgs::Marker > &markers, const std_msgs::ColorRGBA &color) const
Visualize the robot using a markers.
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 3 2020 04:03:08