Abstract class that defines the interface for modelling obstacles. More...
#include <obstacles.h>

Public Member Functions | |
| Obstacle () | |
| Default constructor of the abstract obstacle class. | |
| virtual | ~Obstacle () |
| Virtual destructor. | |
Centroid coordinates (abstract, obstacle type depending) | |
| virtual const Eigen::Vector2d & | getCentroid () const =0 |
| Get centroid coordinates of the obstacle. | |
| virtual std::complex< double > | getCentroidCplx () const =0 |
| Get centroid coordinates of the obstacle as complex number. | |
Collision checking and distance calculations (abstract, obstacle type depending) | |
| virtual bool | checkCollision (const Eigen::Vector2d &position, double min_dist) const =0 |
| Check if a given point collides with the obstacle. | |
| virtual bool | checkLineIntersection (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double min_dist=0) const =0 |
Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance min_dist) | |
| virtual double | getMinimumDistance (const Eigen::Vector2d &position) const =0 |
| Get the minimum euclidean distance to the obstacle (point as reference) | |
| virtual double | getMinimumDistance (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const =0 |
| Get the minimum euclidean distance to the obstacle (line as reference) | |
| virtual double | getMinimumDistance (const Point2dContainer &polygon) const =0 |
| Get the minimum euclidean distance to the obstacle (polygon as reference) | |
| virtual Eigen::Vector2d | getClosestPoint (const Eigen::Vector2d &position) const =0 |
| Get the closest point on the boundary of the obstacle w.r.t. a specified reference position. | |
Velocity related methods for non-static, moving obstacles | |
| bool | isDynamic () const |
| Check if the obstacle is a moving with a (non-zero) velocity. | |
| void | setCentroidVelocity (const Eigen::Ref< const Eigen::Vector2d > &vel) |
| Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid. | |
| const Eigen::Vector2d & | getCentroidVelocity () const |
| Get the obstacle velocity (vx, vy) (w.r.t. to the centroid) | |
Helper Functions | |
| virtual void | toPolygonMsg (geometry_msgs::Polygon &polygon)=0 |
| Convert the obstacle to a polygon message. | |
Protected Attributes | |
| Eigen::Vector2d | centroid_velocity_ |
Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is true) | |
| bool | dynamic_ |
| Store flag if obstacle is dynamic (resp. a moving obstacle) | |
Abstract class that defines the interface for modelling obstacles.
Definition at line 61 of file obstacles.h.
| teb_local_planner::Obstacle::Obstacle | ( | ) | [inline] |
Default constructor of the abstract obstacle class.
Definition at line 68 of file obstacles.h.
| virtual teb_local_planner::Obstacle::~Obstacle | ( | ) | [inline, virtual] |
Virtual destructor.
Definition at line 75 of file obstacles.h.
| virtual bool teb_local_planner::Obstacle::checkCollision | ( | const Eigen::Vector2d & | position, |
| double | min_dist | ||
| ) | const [pure virtual] |
Check if a given point collides with the obstacle.
| position | 2D reference position that should be checked |
| min_dist | Minimum distance allowed to the obstacle to be collision free |
true if position is inside the region of the obstacle or if the minimum distance is lower than min_dist Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| virtual bool teb_local_planner::Obstacle::checkLineIntersection | ( | const Eigen::Vector2d & | line_start, |
| const Eigen::Vector2d & | line_end, | ||
| double | min_dist = 0 |
||
| ) | const [pure virtual] |
Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance min_dist)
| line_start | 2D point for the end of the reference line |
| line_end | 2D point for the end of the reference line |
| min_dist | Minimum distance allowed to the obstacle to be collision/intersection free |
true if given line intersects the region of the obstacle or if the minimum distance is lower than min_dist Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| virtual const Eigen::Vector2d& teb_local_planner::Obstacle::getCentroid | ( | ) | const [pure virtual] |
Get centroid coordinates of the obstacle.
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| virtual std::complex<double> teb_local_planner::Obstacle::getCentroidCplx | ( | ) | const [pure virtual] |
Get centroid coordinates of the obstacle as complex number.
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| const Eigen::Vector2d& teb_local_planner::Obstacle::getCentroidVelocity | ( | ) | const [inline] |
Get the obstacle velocity (vx, vy) (w.r.t. to the centroid)
Definition at line 171 of file obstacles.h.
| virtual Eigen::Vector2d teb_local_planner::Obstacle::getClosestPoint | ( | const Eigen::Vector2d & | position | ) | const [pure virtual] |
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position.
| position | reference 2d position |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| virtual double teb_local_planner::Obstacle::getMinimumDistance | ( | const Eigen::Vector2d & | position | ) | const [pure virtual] |
Get the minimum euclidean distance to the obstacle (point as reference)
| position | 2d reference position |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| virtual double teb_local_planner::Obstacle::getMinimumDistance | ( | const Eigen::Vector2d & | line_start, |
| const Eigen::Vector2d & | line_end | ||
| ) | const [pure virtual] |
Get the minimum euclidean distance to the obstacle (line as reference)
| line_start | 2d position of the begin of the reference line |
| line_end | 2d position of the end of the reference line |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| virtual double teb_local_planner::Obstacle::getMinimumDistance | ( | const Point2dContainer & | polygon | ) | const [pure virtual] |
Get the minimum euclidean distance to the obstacle (polygon as reference)
| polygon | Vertices (2D points) describing a closed polygon |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
| bool teb_local_planner::Obstacle::isDynamic | ( | ) | const [inline] |
Check if the obstacle is a moving with a (non-zero) velocity.
true if the obstacle is not marked as static, false otherwise Definition at line 158 of file obstacles.h.
| void teb_local_planner::Obstacle::setCentroidVelocity | ( | const Eigen::Ref< const Eigen::Vector2d > & | vel | ) | [inline] |
Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid.
| vel | 2D vector containing the velocities of the centroid in x and y directions |
Definition at line 165 of file obstacles.h.
| virtual void teb_local_planner::Obstacle::toPolygonMsg | ( | geometry_msgs::Polygon & | polygon | ) | [pure virtual] |
Convert the obstacle to a polygon message.
Convert the obstacle to a corresponding polygon msg. Point obstacles have one vertex, lines have two vertices and polygons might are implictly closed such that the start vertex must not be repeated.
| [out] | polygon | the polygon message |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, and teb_local_planner::PointObstacle.
Eigen::Vector2d teb_local_planner::Obstacle::centroid_velocity_ [protected] |
Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is true)
Definition at line 195 of file obstacles.h.
bool teb_local_planner::Obstacle::dynamic_ [protected] |
Store flag if obstacle is dynamic (resp. a moving obstacle)
Definition at line 194 of file obstacles.h.