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) More... | |
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 &position) const |
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 |
Get the minimum euclidean distance to the obstacle (line 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 &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 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 Point2dContainer &polygon, double t) const |
Get the estimated minimum spatiotemporal distance to the moving obstacle using a constant velocity model (polygon as reference) More... | |
LineObstacle () | |
Default constructor of the point obstacle class. More... | |
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. More... | |
LineObstacle (double x1, double y1, double x2, double y2) | |
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_ |
Eigen::Vector2d | start_ |
Additional Inherited Members | |
Protected Attributes inherited from teb_local_planner::Obstacle | |
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... | |
Implements a 2D line obstacle.
Definition at line 597 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 601 of file obstacles.h.
|
inline |
Default constructor of the point obstacle class.
Definition at line 606 of file obstacles.h.
|
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 618 of file obstacles.h.
|
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 631 of file obstacles.h.
|
inlineprotected |
Definition at line 728 of file obstacles.h.
|
inlinevirtual |
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 641 of file obstacles.h.
|
inlinevirtual |
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 647 of file obstacles.h.
|
inline |
Definition at line 712 of file obstacles.h.
|
inlinevirtual |
Get centroid coordinates of the obstacle.
Implements teb_local_planner::Obstacle.
Definition at line 698 of file obstacles.h.
|
inlinevirtual |
Get centroid coordinates of the obstacle as complex number.
Implements teb_local_planner::Obstacle.
Definition at line 704 of file obstacles.h.
|
inlinevirtual |
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 671 of file obstacles.h.
|
inlinevirtual |
Get the minimum euclidean distance to the obstacle (point as reference)
position | 2d reference position |
Implements teb_local_planner::Obstacle.
Definition at line 653 of file obstacles.h.
|
inlinevirtual |
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 659 of file obstacles.h.
|
inlinevirtual |
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 665 of file obstacles.h.
|
inlinevirtual |
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 |
Implements teb_local_planner::Obstacle.
Definition at line 677 of file obstacles.h.
|
inlinevirtual |
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 |
Implements teb_local_planner::Obstacle.
Definition at line 684 of file obstacles.h.
|
inlinevirtual |
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 |
Implements teb_local_planner::Obstacle.
Definition at line 691 of file obstacles.h.
|
inline |
Definition at line 713 of file obstacles.h.
|
inline |
Definition at line 711 of file obstacles.h.
|
inline |
Definition at line 710 of file obstacles.h.
|
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.
[out] | polygon | the polygon message |
Implements teb_local_planner::Obstacle.
Definition at line 716 of file obstacles.h.
|
private |
Definition at line 734 of file obstacles.h.
|
private |
Definition at line 732 of file obstacles.h.
|
private |
Definition at line 731 of file obstacles.h.