Implements a 2D line obstacle. More...
#include <obstacles.h>
Public Types | |
typedef std::vector < Eigen::Vector2d, Eigen::aligned_allocator < Eigen::Vector2d > > | VertexContainer |
Abbrev. for a container storing vertices (2d points defining the edge points of the polygon) | |
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 ) | |
const Eigen::Vector2d & | end () const |
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) | |
LineObstacle () | |
Default constructor of the point obstacle class. | |
LineObstacle (const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end) | |
Construct LineObstacle using 2d position vectors as start and end of the line. | |
LineObstacle (double x1, double y1, double x2, double y2) | |
Construct LineObstacle using start and end coordinates. | |
void | setEnd (const Eigen::Ref< const Eigen::Vector2d > &end) |
void | setStart (const Eigen::Ref< const Eigen::Vector2d > &start) |
const Eigen::Vector2d & | start () const |
virtual void | toPolygonMsg (geometry_msgs::Polygon &polygon) |
Convert the obstacle to a polygon message. | |
Protected Member Functions | |
void | calcCentroid () |
Private Attributes | |
Eigen::Vector2d | centroid_ |
Eigen::Vector2d | end_ |
Eigen::Vector2d | start_ |
Implements a 2D line obstacle.
Definition at line 337 of file obstacles.h.
typedef std::vector<Eigen::Vector2d,Eigen::aligned_allocator<Eigen::Vector2d> > teb_local_planner::LineObstacle::VertexContainer |
Abbrev. for a container storing vertices (2d points defining the edge points of the polygon)
Definition at line 341 of file obstacles.h.
teb_local_planner::LineObstacle::LineObstacle | ( | ) | [inline] |
Default constructor of the point obstacle class.
Definition at line 346 of file obstacles.h.
teb_local_planner::LineObstacle::LineObstacle | ( | const Eigen::Ref< const Eigen::Vector2d > & | line_start, |
const Eigen::Ref< const Eigen::Vector2d > & | line_end | ||
) | [inline] |
Construct LineObstacle using 2d position vectors as start and end of the line.
line_start | 2d position that defines the start of the line obstacle |
line_end | 2d position that defines the end of the line obstacle |
Definition at line 358 of file obstacles.h.
teb_local_planner::LineObstacle::LineObstacle | ( | double | x1, |
double | y1, | ||
double | x2, | ||
double | y2 | ||
) | [inline] |
Construct LineObstacle using start and end coordinates.
x1 | x-coordinate of the start of the line |
y1 | y-coordinate of the start of the line |
x2 | x-coordinate of the end of the line |
y2 | y-coordinate of the end of the line |
Definition at line 371 of file obstacles.h.
void teb_local_planner::LineObstacle::calcCentroid | ( | ) | [inline, protected] |
Definition at line 449 of file obstacles.h.
virtual bool teb_local_planner::LineObstacle::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 381 of file obstacles.h.
virtual bool teb_local_planner::LineObstacle::checkLineIntersection | ( | const Eigen::Vector2d & | line_start, |
const Eigen::Vector2d & | line_end, | ||
double | min_dist = 0 |
||
) | const [inline, 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 Implements teb_local_planner::Obstacle.
Definition at line 387 of file obstacles.h.
const Eigen::Vector2d& teb_local_planner::LineObstacle::end | ( | ) | const [inline] |
Definition at line 433 of file obstacles.h.
virtual const Eigen::Vector2d& teb_local_planner::LineObstacle::getCentroid | ( | ) | const [inline, virtual] |
Get centroid coordinates of the obstacle.
Implements teb_local_planner::Obstacle.
Definition at line 419 of file obstacles.h.
virtual std::complex<double> teb_local_planner::LineObstacle::getCentroidCplx | ( | ) | const [inline, virtual] |
Get centroid coordinates of the obstacle as complex number.
Implements teb_local_planner::Obstacle.
Definition at line 425 of file obstacles.h.
virtual Eigen::Vector2d teb_local_planner::LineObstacle::getClosestPoint | ( | const Eigen::Vector2d & | position | ) | const [inline, 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 411 of file obstacles.h.
virtual double teb_local_planner::LineObstacle::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 393 of file obstacles.h.
virtual double teb_local_planner::LineObstacle::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 399 of file obstacles.h.
virtual double teb_local_planner::LineObstacle::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 405 of file obstacles.h.
void teb_local_planner::LineObstacle::setEnd | ( | const Eigen::Ref< const Eigen::Vector2d > & | end | ) | [inline] |
Definition at line 434 of file obstacles.h.
void teb_local_planner::LineObstacle::setStart | ( | const Eigen::Ref< const Eigen::Vector2d > & | start | ) | [inline] |
Definition at line 432 of file obstacles.h.
const Eigen::Vector2d& teb_local_planner::LineObstacle::start | ( | ) | const [inline] |
Definition at line 431 of file obstacles.h.
virtual void teb_local_planner::LineObstacle::toPolygonMsg | ( | geometry_msgs::Polygon & | polygon | ) | [inline, 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 437 of file obstacles.h.
Eigen::Vector2d teb_local_planner::LineObstacle::centroid_ [private] |
Definition at line 455 of file obstacles.h.
Eigen::Vector2d teb_local_planner::LineObstacle::end_ [private] |
Definition at line 453 of file obstacles.h.
Eigen::Vector2d teb_local_planner::LineObstacle::start_ [private] |
Definition at line 452 of file obstacles.h.