Public Member Functions | Protected Member Functions | Protected Attributes
teb_local_planner::PolygonObstacle Class Reference

Implements a polygon obstacle with an arbitrary number of vertices. More...

#include <obstacles.h>

Inheritance diagram for teb_local_planner::PolygonObstacle:
Inheritance graph
[legend]

List of all members.

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.
virtual void toPolygonMsg (geometry_msgs::Polygon &polygon)
 Convert the obstacle to a polygon message.
Define the polygon
const Point2dContainervertices () const
Point2dContainervertices ()
 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)
size_t 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 (.

Detailed Description

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.


Constructor & Destructor Documentation

Default constructor of the polygon obstacle class.

Definition at line 476 of file obstacles.h.


Member Function Documentation

Compute the centroid of the polygon (called inside finalizePolygon())

Definition at line 56 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.

Parameters:
position2D reference position that should be checked
min_distMinimum distance allowed to the obstacle to be collision free
Returns:
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 494 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)

Parameters:
line_start2D point for the end of the reference line
line_end2D point for the end of the reference line
min_distMinimum distance allowed to the obstacle to be collision/intersection free
Remarks:
we ignore min_dist here
Returns:
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 177 of file obstacles.cpp.

Clear all vertices (Afterwards the polygon is not valid anymore)

Definition at line 614 of file obstacles.h.

Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods.

Definition at line 604 of file obstacles.h.

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 47 of file obstacles.cpp.

virtual const Eigen::Vector2d& teb_local_planner::PolygonObstacle::getCentroid ( ) const [inline, virtual]

Get centroid coordinates of the obstacle.

Returns:
Eigen::Vector2d containing the centroid

Implements teb_local_planner::Obstacle.

Definition at line 552 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.

Returns:
std::complex containing the centroid coordinate

Implements teb_local_planner::Obstacle.

Definition at line 559 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.

Parameters:
positionreference 2d position
Returns:
closest point on the obstacle boundary

Implements teb_local_planner::Obstacle.

Definition at line 129 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)

Parameters:
position2d reference position
Returns:
The nearest possible distance to the obstacle

Implements teb_local_planner::Obstacle.

Definition at line 531 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)

Parameters:
line_start2d position of the begin of the reference line
line_end2d position of the end of the reference line
Returns:
The nearest possible distance to the obstacle

Implements teb_local_planner::Obstacle.

Definition at line 537 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)

Parameters:
polygonVertices (2D points) describing a closed polygon
Returns:
The nearest possible distance to the obstacle

Implements teb_local_planner::Obstacle.

Definition at line 543 of file obstacles.h.

Get the number of vertices defining the polygon (the first vertex is counted once)

Definition at line 619 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)

Remarks:
You do not need to close the polygon (do not repeat the first vertex)
Warning:
Do not forget to call finalizePolygon() after adding all vertices
Parameters:
vertex2D point defining a new polygon edge

Definition at line 582 of file obstacles.h.

void teb_local_planner::PolygonObstacle::pushBackVertex ( double  x,
double  y 
) [inline]

Add a vertex to the polygon (edge-point)

Remarks:
You do not need to close the polygon (do not repeat the first vertex)
Warning:
Do not forget to call finalizePolygon() after adding all vertices
Parameters:
xx-coordinate of the new vertex
yy-coordinate of the new vertex

Definition at line 595 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.

Parameters:
[out]polygonthe polygon message

Implements teb_local_planner::Obstacle.

Definition at line 195 of file obstacles.cpp.

Access vertices container (read-only)

Definition at line 573 of file obstacles.h.

Access vertices container.

Definition at line 574 of file obstacles.h.


Member Data Documentation

Eigen::Vector2d teb_local_planner::PolygonObstacle::centroid_ [protected]

Store the centroid coordinates of the polygon (.

See also:
calcCentroid)

Definition at line 632 of file obstacles.h.

Flat that keeps track if the polygon was finalized after adding all vertices.

Definition at line 634 of file obstacles.h.

Store vertices defining the polygon (.

See also:
pushBackVertex)

Definition at line 631 of file obstacles.h.


The documentation for this class was generated from the following files:


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:16