Public Member Functions | Protected Member Functions | Private Attributes | List of all members
teb_local_planner::PillObstacle Class Reference

Implements a 2D pill/stadium/capsular-shaped obstacle (line + distance/radius) More...

#include <obstacles.h>

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

Public Member Functions

virtual bool checkCollision (const Eigen::Vector2d &point, double min_dist) const
 Check if a given point collides with the obstacle. More...
 
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) More...
 
const Eigen::Vector2d & end () const
 
virtual const Eigen::Vector2d & getCentroid () const
 Get centroid coordinates of the obstacle. More...
 
virtual std::complex< double > getCentroidCplx () const
 Get centroid coordinates of the obstacle as complex number. More...
 
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. More...
 
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) More...
 
virtual double getMinimumDistance (const Eigen::Vector2d &position) const
 Get the minimum euclidean distance to the obstacle (point as reference) More...
 
virtual double getMinimumDistance (const Point2dContainer &polygon) const
 Get the minimum euclidean distance to the obstacle (polygon as reference) More...
 
virtual double getMinimumSpatioTemporalDistance (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const
 Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (line as reference) More...
 
virtual double getMinimumSpatioTemporalDistance (const Eigen::Vector2d &position, double t) const
 Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (point as reference) More...
 
virtual double getMinimumSpatioTemporalDistance (const Point2dContainer &polygon, double t) const
 Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (polygon as reference) More...
 
 PillObstacle ()
 Default constructor of the point obstacle class. More...
 
 PillObstacle (const Eigen::Ref< const Eigen::Vector2d > &line_start, const Eigen::Ref< const Eigen::Vector2d > &line_end, double radius)
 Construct LineObstacle using 2d position vectors as start and end of the line. More...
 
 PillObstacle (double x1, double y1, double x2, double y2, double radius)
 Construct LineObstacle using start and end coordinates. More...
 
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. More...
 
- Public Member Functions inherited from teb_local_planner::Obstacle
 Obstacle ()
 Default constructor of the abstract obstacle class. More...
 
virtual ~Obstacle ()
 Virtual destructor. More...
 
virtual void predictCentroidConstantVelocity (double t, Eigen::Ref< Eigen::Vector2d > position) const
 Predict position of the centroid assuming a constant velocity model. More...
 
bool isDynamic () const
 Check if the obstacle is a moving with a (non-zero) velocity. More...
 
void setCentroidVelocity (const Eigen::Ref< const Eigen::Vector2d > &vel)
 Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid. More...
 
void setCentroidVelocity (const geometry_msgs::TwistWithCovariance &velocity, const geometry_msgs::Quaternion &orientation)
 Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid. More...
 
void setCentroidVelocity (const geometry_msgs::TwistWithCovariance &velocity, const geometry_msgs::QuaternionStamped &orientation)
 
const Eigen::Vector2d & getCentroidVelocity () const
 Get the obstacle velocity (vx, vy) (w.r.t. to the centroid) More...
 
virtual void toTwistWithCovarianceMsg (geometry_msgs::TwistWithCovariance &twistWithCovariance)
 

Protected Member Functions

void calcCentroid ()
 

Private Attributes

Eigen::Vector2d centroid_
 
Eigen::Vector2d end_
 
double radius_ = 0.0
 
Eigen::Vector2d start_
 

Additional Inherited Members

- Protected Attributes inherited from teb_local_planner::Obstacle
bool dynamic_
 Store flag if obstacle is dynamic (resp. a moving obstacle) More...
 
Eigen::Vector2d centroid_velocity_
 Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is true) More...
 

Detailed Description

Implements a 2D pill/stadium/capsular-shaped obstacle (line + distance/radius)

Definition at line 782 of file obstacles.h.

Constructor & Destructor Documentation

◆ PillObstacle() [1/3]

teb_local_planner::PillObstacle::PillObstacle ( )
inline

Default constructor of the point obstacle class.

Definition at line 789 of file obstacles.h.

◆ PillObstacle() [2/3]

teb_local_planner::PillObstacle::PillObstacle ( const Eigen::Ref< const Eigen::Vector2d > &  line_start,
const Eigen::Ref< const Eigen::Vector2d > &  line_end,
double  radius 
)
inline

Construct LineObstacle using 2d position vectors as start and end of the line.

Parameters
line_start2d position that defines the start of the line obstacle
line_end2d position that defines the end of the line obstacle

Definition at line 801 of file obstacles.h.

◆ PillObstacle() [3/3]

teb_local_planner::PillObstacle::PillObstacle ( double  x1,
double  y1,
double  x2,
double  y2,
double  radius 
)
inline

Construct LineObstacle using start and end coordinates.

Parameters
x1x-coordinate of the start of the line
y1y-coordinate of the start of the line
x2x-coordinate of the end of the line
y2y-coordinate of the end of the line

Definition at line 814 of file obstacles.h.

Member Function Documentation

◆ calcCentroid()

void teb_local_planner::PillObstacle::calcCentroid ( )
inlineprotected

Definition at line 914 of file obstacles.h.

◆ checkCollision()

virtual bool teb_local_planner::PillObstacle::checkCollision ( const Eigen::Vector2d &  position,
double  min_dist 
) const
inlinevirtual

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

◆ checkLineIntersection()

virtual bool teb_local_planner::PillObstacle::checkLineIntersection ( const Eigen::Vector2d &  line_start,
const Eigen::Vector2d &  line_end,
double  min_dist = 0 
) const
inlinevirtual

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

◆ end()

const Eigen::Vector2d& teb_local_planner::PillObstacle::end ( ) const
inline

Definition at line 896 of file obstacles.h.

◆ getCentroid()

virtual const Eigen::Vector2d& teb_local_planner::PillObstacle::getCentroid ( ) const
inlinevirtual

Get centroid coordinates of the obstacle.

Returns
Eigen::Vector2d containing the centroid

Implements teb_local_planner::Obstacle.

Definition at line 882 of file obstacles.h.

◆ getCentroidCplx()

virtual std::complex<double> teb_local_planner::PillObstacle::getCentroidCplx ( ) const
inlinevirtual

Get centroid coordinates of the obstacle as complex number.

Returns
std::complex containing the centroid coordinate

Implements teb_local_planner::Obstacle.

Definition at line 888 of file obstacles.h.

◆ getClosestPoint()

virtual Eigen::Vector2d teb_local_planner::PillObstacle::getClosestPoint ( const Eigen::Vector2d &  position) const
inlinevirtual

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

◆ getMinimumDistance() [1/3]

virtual double teb_local_planner::PillObstacle::getMinimumDistance ( const Eigen::Vector2d &  line_start,
const Eigen::Vector2d &  line_end 
) const
inlinevirtual

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

◆ getMinimumDistance() [2/3]

virtual double teb_local_planner::PillObstacle::getMinimumDistance ( const Eigen::Vector2d &  position) const
inlinevirtual

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

◆ getMinimumDistance() [3/3]

virtual double teb_local_planner::PillObstacle::getMinimumDistance ( const Point2dContainer polygon) const
inlinevirtual

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

◆ getMinimumSpatioTemporalDistance() [1/3]

virtual double teb_local_planner::PillObstacle::getMinimumSpatioTemporalDistance ( const Eigen::Vector2d &  line_start,
const Eigen::Vector2d &  line_end,
double  t 
) const
inlinevirtual

Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (line as reference)

Parameters
line_start2d position of the begin of the reference line
line_end2d position of the end of the reference line
ttime, for which the minimum distance to the obstacle is estimated
Returns
The nearest possible distance to the obstacle at time t

Implements teb_local_planner::Obstacle.

Definition at line 868 of file obstacles.h.

◆ getMinimumSpatioTemporalDistance() [2/3]

virtual double teb_local_planner::PillObstacle::getMinimumSpatioTemporalDistance ( const Eigen::Vector2d &  position,
double  t 
) const
inlinevirtual

Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (point as reference)

Parameters
position2d reference position
ttime, for which the minimum distance to the obstacle is estimated
Returns
The nearest possible distance to the obstacle at time t

Implements teb_local_planner::Obstacle.

Definition at line 861 of file obstacles.h.

◆ getMinimumSpatioTemporalDistance() [3/3]

virtual double teb_local_planner::PillObstacle::getMinimumSpatioTemporalDistance ( const Point2dContainer polygon,
double  t 
) const
inlinevirtual

Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (polygon as reference)

Parameters
polygonVertices (2D points) describing a closed polygon
ttime, for which the minimum distance to the obstacle is estimated
Returns
The nearest possible distance to the obstacle at time t

Implements teb_local_planner::Obstacle.

Definition at line 875 of file obstacles.h.

◆ setEnd()

void teb_local_planner::PillObstacle::setEnd ( const Eigen::Ref< const Eigen::Vector2d > &  end)
inline

Definition at line 897 of file obstacles.h.

◆ setStart()

void teb_local_planner::PillObstacle::setStart ( const Eigen::Ref< const Eigen::Vector2d > &  start)
inline

Definition at line 895 of file obstacles.h.

◆ start()

const Eigen::Vector2d& teb_local_planner::PillObstacle::start ( ) const
inline

Definition at line 894 of file obstacles.h.

◆ toPolygonMsg()

virtual void teb_local_planner::PillObstacle::toPolygonMsg ( geometry_msgs::Polygon &  polygon)
inlinevirtual

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

Member Data Documentation

◆ centroid_

Eigen::Vector2d teb_local_planner::PillObstacle::centroid_
private

Definition at line 921 of file obstacles.h.

◆ end_

Eigen::Vector2d teb_local_planner::PillObstacle::end_
private

Definition at line 918 of file obstacles.h.

◆ radius_

double teb_local_planner::PillObstacle::radius_ = 0.0
private

Definition at line 919 of file obstacles.h.

◆ start_

Eigen::Vector2d teb_local_planner::PillObstacle::start_
private

Definition at line 917 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 Sun Jan 7 2024 03:45:15