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

Implements a 2D point obstacle. More...

#include <obstacles.h>

Inheritance diagram for teb_local_planner::PointObstacle:
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)
 PointObstacle ()
 Default constructor of the point obstacle class.
 PointObstacle (const Eigen::Ref< const Eigen::Vector2d > &position)
 Construct PointObstacle using a 2d position vector.
 PointObstacle (double x, double y)
 Construct PointObstacle using x- and y-coordinates.
const Eigen::Vector2d & position () const
 Return the current position of the obstacle (read-only)
Eigen::Vector2d & position ()
 Return the current position of the obstacle.
virtual void toPolygonMsg (geometry_msgs::Polygon &polygon)
 Convert the obstacle to a polygon message.
double & x ()
 Return the current x-coordinate of the obstacle.
const double & x () const
 Return the current y-coordinate of the obstacle (read-only)
double & y ()
 Return the current x-coordinate of the obstacle.
const double & y () const
 Return the current y-coordinate of the obstacle (read-only)

Protected Attributes

Eigen::Vector2d pos_
 Store the position of the PointObstacle.

Detailed Description

Implements a 2D point obstacle.

Definition at line 215 of file obstacles.h.


Constructor & Destructor Documentation

Default constructor of the point obstacle class.

Definition at line 222 of file obstacles.h.

teb_local_planner::PointObstacle::PointObstacle ( const Eigen::Ref< const Eigen::Vector2d > &  position) [inline]

Construct PointObstacle using a 2d position vector.

Parameters:
position2d position that defines the current obstacle position

Definition at line 229 of file obstacles.h.

teb_local_planner::PointObstacle::PointObstacle ( double  x,
double  y 
) [inline]

Construct PointObstacle using x- and y-coordinates.

Parameters:
xx-coordinate
yy-coordinate

Definition at line 237 of file obstacles.h.


Member Function Documentation

virtual bool teb_local_planner::PointObstacle::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 242 of file obstacles.h.

virtual bool teb_local_planner::PointObstacle::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)

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
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 249 of file obstacles.h.

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

Get centroid coordinates of the obstacle.

Returns:
Eigen::Vector2d containing the centroid

Implements teb_local_planner::Obstacle.

Definition at line 292 of file obstacles.h.

virtual std::complex<double> teb_local_planner::PointObstacle::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 299 of file obstacles.h.

virtual Eigen::Vector2d teb_local_planner::PointObstacle::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.

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

Implements teb_local_planner::Obstacle.

Definition at line 286 of file obstacles.h.

virtual double teb_local_planner::PointObstacle::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 268 of file obstacles.h.

virtual double teb_local_planner::PointObstacle::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 274 of file obstacles.h.

virtual double teb_local_planner::PointObstacle::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 280 of file obstacles.h.

const Eigen::Vector2d& teb_local_planner::PointObstacle::position ( ) const [inline]

Return the current position of the obstacle (read-only)

Definition at line 305 of file obstacles.h.

Eigen::Vector2d& teb_local_planner::PointObstacle::position ( ) [inline]

Return the current position of the obstacle.

Definition at line 306 of file obstacles.h.

virtual void teb_local_planner::PointObstacle::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.

Parameters:
[out]polygonthe polygon message

Implements teb_local_planner::Obstacle.

Definition at line 313 of file obstacles.h.

Return the current x-coordinate of the obstacle.

Definition at line 307 of file obstacles.h.

const double& teb_local_planner::PointObstacle::x ( ) const [inline]

Return the current y-coordinate of the obstacle (read-only)

Definition at line 308 of file obstacles.h.

Return the current x-coordinate of the obstacle.

Definition at line 309 of file obstacles.h.

const double& teb_local_planner::PointObstacle::y ( ) const [inline]

Return the current y-coordinate of the obstacle (read-only)

Definition at line 310 of file obstacles.h.


Member Data Documentation

Eigen::Vector2d teb_local_planner::PointObstacle::pos_ [protected]

Store the position of the PointObstacle.

Definition at line 323 of file obstacles.h.


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


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