Abstract class that defines the interface for modelling obstacles. More...
#include <obstacles.h>
Public Member Functions | |
Obstacle () | |
Default constructor of the abstract obstacle class. More... | |
virtual | ~Obstacle () |
Virtual destructor. More... | |
Centroid coordinates (abstract, obstacle type depending) | |
virtual const Eigen::Vector2d & | getCentroid () const =0 |
Get centroid coordinates of the obstacle. More... | |
virtual std::complex< double > | getCentroidCplx () const =0 |
Get centroid coordinates of the obstacle as complex number. More... | |
Collision checking and distance calculations (abstract, obstacle type depending) | |
virtual bool | checkCollision (const Eigen::Vector2d &position, double min_dist) const =0 |
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 =0 |
Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance min_dist ) More... | |
virtual double | getMinimumDistance (const Eigen::Vector2d &position) const =0 |
Get the minimum euclidean distance to the obstacle (point as reference) More... | |
virtual double | getMinimumDistance (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const =0 |
Get the minimum euclidean distance to the obstacle (line as reference) More... | |
virtual double | getMinimumDistance (const Point2dContainer &polygon) const =0 |
Get the minimum euclidean distance to the obstacle (polygon as reference) More... | |
virtual Eigen::Vector2d | getClosestPoint (const Eigen::Vector2d &position) const =0 |
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position. More... | |
Velocity related methods for non-static, moving obstacles | |
virtual double | getMinimumSpatioTemporalDistance (const Eigen::Vector2d &position, double t) const =0 |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (point as reference) More... | |
virtual double | getMinimumSpatioTemporalDistance (const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const =0 |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (line as reference) More... | |
virtual double | getMinimumSpatioTemporalDistance (const Point2dContainer &polygon, double t) const =0 |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (polygon as reference) 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... | |
Helper Functions | |
virtual void | toPolygonMsg (geometry_msgs::Polygon &polygon)=0 |
Convert the obstacle to a polygon message. More... | |
virtual void | toTwistWithCovarianceMsg (geometry_msgs::TwistWithCovariance &twistWithCovariance) |
Protected Attributes | |
Eigen::Vector2d | centroid_velocity_ |
Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is true ) More... | |
bool | dynamic_ |
Store flag if obstacle is dynamic (resp. a moving obstacle) More... | |
Abstract class that defines the interface for modelling obstacles.
Definition at line 67 of file obstacles.h.
|
inline |
Default constructor of the abstract obstacle class.
Definition at line 74 of file obstacles.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 81 of file obstacles.h.
|
pure 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 Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure 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 Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get centroid coordinates of the obstacle.
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get centroid coordinates of the obstacle as complex number.
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
inline |
Get the obstacle velocity (vx, vy) (w.r.t. to the centroid)
Definition at line 245 of file obstacles.h.
|
pure virtual |
Get the closest point on the boundary of the obstacle w.r.t. a specified reference position.
position | reference 2d position |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get the minimum euclidean distance to the obstacle (point as reference)
position | 2d reference position |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure 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 |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get the minimum euclidean distance to the obstacle (polygon as reference)
polygon | Vertices (2D points) describing a closed polygon |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (point as reference)
position | 2d reference position |
t | time, for which the minimum distance to the obstacle is estimated |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (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 |
t | time, for which the minimum distance to the obstacle is estimated |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
pure virtual |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (polygon as reference)
polygon | Vertices (2D points) describing a closed polygon |
t | time, for which the minimum distance to the obstacle is estimated |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
inline |
Check if the obstacle is a moving with a (non-zero) velocity.
true
if the obstacle is not marked as static, false
otherwise Definition at line 199 of file obstacles.h.
|
inlinevirtual |
Predict position of the centroid assuming a constant velocity model.
[in] | t | time in seconds for the prediction (t>=0) |
[out] | position | predicted 2d position of the centroid |
Reimplemented in teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
Definition at line 190 of file obstacles.h.
|
inline |
Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid.
vel | 2D vector containing the velocities of the centroid in x and y directions |
Definition at line 206 of file obstacles.h.
|
inline |
Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid.
velocity | geometry_msgs::TwistWithCovariance containing the velocity of the obstacle |
orientation | geometry_msgs::QuaternionStamped containing the orientation of the obstacle |
Definition at line 214 of file obstacles.h.
|
inline |
Definition at line 235 of file obstacles.h.
|
pure 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 |
Implemented in teb_local_planner::PolygonObstacle, teb_local_planner::LineObstacle, teb_local_planner::CircularObstacle, and teb_local_planner::PointObstacle.
|
inlinevirtual |
Definition at line 264 of file obstacles.h.
|
protected |
Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is true
)
Definition at line 285 of file obstacles.h.
|
protected |
Store flag if obstacle is dynamic (resp. a moving obstacle)
Definition at line 284 of file obstacles.h.