Implements a polygon obstacle with an arbitrary number of vertices. More...
#include <obstacles.h>
Public Member Functions | |
virtual bool | checkCollision (const Eigen::Vector2d &point, double min_dist) const |
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 |
Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance min_dist ) | |
virtual const Eigen::Vector2d & | getCentroid () const |
Get centroid coordinates of the obstacle. | |
virtual std::complex< double > | getCentroidCplx () const |
Get centroid coordinates of the obstacle as complex number. | |
virtual Eigen::Vector2d | getClosestPoint (const Eigen::Vector2d &position) const |
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position. | |
virtual double | getMinimumDistance (const Eigen::Vector2d &position) const |
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 |
Get the minimum euclidean distance to the obstacle (line as reference) | |
virtual double | getMinimumDistance (const Point2dContainer &polygon) const |
Get the minimum euclidean distance to the obstacle (polygon as reference) | |
PolygonObstacle () | |
Default constructor of the polygon obstacle class. | |
PolygonObstacle (const Point2dContainer &vertices) | |
Construct polygon obstacle with a list of vertices. | |
virtual void | toPolygonMsg (geometry_msgs::Polygon &polygon) |
Convert the obstacle to a polygon message. | |
Define the polygon | |
const Point2dContainer & | vertices () const |
Point2dContainer & | vertices () |
Access vertices container. | |
void | pushBackVertex (const Eigen::Ref< const Eigen::Vector2d > &vertex) |
Add a vertex to the polygon (edge-point) | |
void | pushBackVertex (double x, double y) |
Add a vertex to the polygon (edge-point) | |
void | finalizePolygon () |
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods. | |
void | clearVertices () |
Clear all vertices (Afterwards the polygon is not valid anymore) | |
int | noVertices () const |
Get the number of vertices defining the polygon (the first vertex is counted once) | |
Protected Member Functions | |
void | calcCentroid () |
Compute the centroid of the polygon (called inside finalizePolygon()) | |
void | fixPolygonClosure () |
Check if the current polygon contains the first vertex twice (as start and end) and in that case erase the last redundant one. | |
Protected Attributes | |
Eigen::Vector2d | centroid_ |
Store the centroid coordinates of the polygon (. | |
bool | finalized_ |
Flat that keeps track if the polygon was finalized after adding all vertices. | |
Point2dContainer | vertices_ |
Store vertices defining the polygon (. |
Implements a polygon obstacle with an arbitrary number of vertices.
If the polygon has only 2 vertices, than it is considered as a line, otherwise the polygon will always be closed (a connection between the first and the last vertex is included automatically).
Definition at line 469 of file obstacles.h.
teb_local_planner::PolygonObstacle::PolygonObstacle | ( | ) | [inline] |
Default constructor of the polygon obstacle class.
Definition at line 476 of file obstacles.h.
teb_local_planner::PolygonObstacle::PolygonObstacle | ( | const Point2dContainer & | vertices | ) | [inline] |
Construct polygon obstacle with a list of vertices.
Definition at line 484 of file obstacles.h.
void teb_local_planner::PolygonObstacle::calcCentroid | ( | ) | [protected] |
Compute the centroid of the polygon (called inside finalizePolygon())
Definition at line 57 of file obstacles.cpp.
virtual bool teb_local_planner::PolygonObstacle::checkCollision | ( | const Eigen::Vector2d & | position, |
double | min_dist | ||
) | const [inline, 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 Implements teb_local_planner::Obstacle.
Definition at line 502 of file obstacles.h.
bool teb_local_planner::PolygonObstacle::checkLineIntersection | ( | const Eigen::Vector2d & | line_start, |
const Eigen::Vector2d & | line_end, | ||
double | min_dist = 0 |
||
) | const [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 |
min_dist
here true
if given line intersects the region of the obstacle or if the minimum distance is lower than min_dist Implements teb_local_planner::Obstacle.
Definition at line 178 of file obstacles.cpp.
void teb_local_planner::PolygonObstacle::clearVertices | ( | ) | [inline] |
Clear all vertices (Afterwards the polygon is not valid anymore)
Definition at line 622 of file obstacles.h.
void teb_local_planner::PolygonObstacle::finalizePolygon | ( | ) | [inline] |
Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods.
Definition at line 612 of file obstacles.h.
void teb_local_planner::PolygonObstacle::fixPolygonClosure | ( | ) | [protected] |
Check if the current polygon contains the first vertex twice (as start and end) and in that case erase the last redundant one.
Definition at line 48 of file obstacles.cpp.
virtual const Eigen::Vector2d& teb_local_planner::PolygonObstacle::getCentroid | ( | ) | const [inline, virtual] |
Get centroid coordinates of the obstacle.
Implements teb_local_planner::Obstacle.
Definition at line 560 of file obstacles.h.
virtual std::complex<double> teb_local_planner::PolygonObstacle::getCentroidCplx | ( | ) | const [inline, virtual] |
Get centroid coordinates of the obstacle as complex number.
Implements teb_local_planner::Obstacle.
Definition at line 567 of file obstacles.h.
Eigen::Vector2d teb_local_planner::PolygonObstacle::getClosestPoint | ( | const Eigen::Vector2d & | position | ) | const [virtual] |
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position.
position | reference 2d position |
Implements teb_local_planner::Obstacle.
Definition at line 130 of file obstacles.cpp.
virtual double teb_local_planner::PolygonObstacle::getMinimumDistance | ( | const Eigen::Vector2d & | position | ) | const [inline, virtual] |
Get the minimum euclidean distance to the obstacle (point as reference)
position | 2d reference position |
Implements teb_local_planner::Obstacle.
Definition at line 539 of file obstacles.h.
virtual double teb_local_planner::PolygonObstacle::getMinimumDistance | ( | const Eigen::Vector2d & | line_start, |
const Eigen::Vector2d & | line_end | ||
) | const [inline, 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 |
Implements teb_local_planner::Obstacle.
Definition at line 545 of file obstacles.h.
virtual double teb_local_planner::PolygonObstacle::getMinimumDistance | ( | const Point2dContainer & | polygon | ) | const [inline, virtual] |
Get the minimum euclidean distance to the obstacle (polygon as reference)
polygon | Vertices (2D points) describing a closed polygon |
Implements teb_local_planner::Obstacle.
Definition at line 551 of file obstacles.h.
int teb_local_planner::PolygonObstacle::noVertices | ( | ) | const [inline] |
Get the number of vertices defining the polygon (the first vertex is counted once)
Definition at line 627 of file obstacles.h.
void teb_local_planner::PolygonObstacle::pushBackVertex | ( | const Eigen::Ref< const Eigen::Vector2d > & | vertex | ) | [inline] |
Add a vertex to the polygon (edge-point)
vertex | 2D point defining a new polygon edge |
Definition at line 590 of file obstacles.h.
void teb_local_planner::PolygonObstacle::pushBackVertex | ( | double | x, |
double | y | ||
) | [inline] |
Add a vertex to the polygon (edge-point)
x | x-coordinate of the new vertex |
y | y-coordinate of the new vertex |
Definition at line 603 of file obstacles.h.
void teb_local_planner::PolygonObstacle::toPolygonMsg | ( | geometry_msgs::Polygon & | polygon | ) | [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 |
Implements teb_local_planner::Obstacle.
Definition at line 196 of file obstacles.cpp.
const Point2dContainer& teb_local_planner::PolygonObstacle::vertices | ( | ) | const [inline] |
Access vertices container (read-only)
Definition at line 581 of file obstacles.h.
Point2dContainer& teb_local_planner::PolygonObstacle::vertices | ( | ) | [inline] |
Access vertices container.
Definition at line 582 of file obstacles.h.
Eigen::Vector2d teb_local_planner::PolygonObstacle::centroid_ [protected] |
Store the centroid coordinates of the polygon (.
Definition at line 640 of file obstacles.h.
bool teb_local_planner::PolygonObstacle::finalized_ [protected] |
Flat that keeps track if the polygon was finalized after adding all vertices.
Definition at line 642 of file obstacles.h.
Store vertices defining the polygon (.
Definition at line 639 of file obstacles.h.