Class LineObstacle

Inheritance Relationships

Base Type

Class Documentation

class LineObstacle : public hateb_local_planner::Obstacle

Implements a 2D line obstacle.

Public Types

using VertexContainer = std::vector<Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d>>

Abbrev. for a container storing vertices (2d points defining the edge points of the polygon)

Public Functions

inline LineObstacle()

Default constructor of the point obstacle class.

inline 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.

Parameters:
  • line_start – 2d position that defines the start of the line obstacle

  • line_end – 2d position that defines the end of the line obstacle

inline LineObstacle(double x1, double y1, double x2, double y2)

Construct LineObstacle using start and end coordinates.

Parameters:
  • 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

inline virtual bool checkCollision(const Eigen::Vector2d &point, double min_dist) const override

Check if a given point collides with the obstacle.

Parameters:
  • position – 2D reference position that should be checked

  • min_dist – Minimum 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

inline virtual bool checkLineIntersection(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double min_dist = 0) const override

Check if a given line segment between two points intersects with the obstacle (and additionally keeps a safty distance min_dist)

Parameters:
  • 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

Returns:

true if given line intersects the region of the obstacle or if the minimum distance is lower than min_dist

inline virtual double getMinimumDistance(const Eigen::Vector2d &position) const override

Get the minimum euclidean distance to the obstacle (point as reference)

Parameters:

position – 2d reference position

Returns:

The nearest possible distance to the obstacle

inline virtual double getMinimumDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end) const override

Get the minimum euclidean distance to the obstacle (line as reference)

Parameters:
  • line_start – 2d position of the begin of the reference line

  • line_end – 2d position of the end of the reference line

Returns:

The nearest possible distance to the obstacle

inline virtual double getMinimumDistance(const Point2dContainer &polygon) const override

Get the minimum euclidean distance to the obstacle (polygon as reference)

Parameters:

polygon – Vertices (2D points) describing a closed polygon

Returns:

The nearest possible distance to the obstacle

inline virtual Eigen::Vector2d getClosestPoint(const Eigen::Vector2d &position) const override

Get the closest point on the boundary of the obstacle w.r.t. a specified reference position.

Parameters:

position – reference 2d position

Returns:

closest point on the obstacle boundary

inline virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &position, double t) const override

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

Parameters:
  • position – 2d reference position

  • t – time, for which the minimum distance to the obstacle is estimated

Returns:

The nearest possible distance to the obstacle at time t

inline virtual double getMinimumSpatioTemporalDistance(const Eigen::Vector2d &line_start, const Eigen::Vector2d &line_end, double t) const override

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

Parameters:
  • 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

Returns:

The nearest possible distance to the obstacle at time t

inline virtual double getMinimumSpatioTemporalDistance(const Point2dContainer &polygon, double t) const override

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

Parameters:
  • polygon – Vertices (2D points) describing a closed polygon

  • t – time, for which the minimum distance to the obstacle is estimated

Returns:

The nearest possible distance to the obstacle at time t

inline virtual const Eigen::Vector2d &getCentroid() const override

Get centroid coordinates of the obstacle.

Returns:

Eigen::Vector2d containing the centroid

inline virtual std::complex<double> getCentroidCplx() const override

Get centroid coordinates of the obstacle as complex number.

Returns:

std::complex containing the centroid coordinate

inline const Eigen::Vector2d &start() const
inline void setStart(const Eigen::Ref<const Eigen::Vector2d> &start)
inline const Eigen::Vector2d &end() const
inline void setEnd(const Eigen::Ref<const Eigen::Vector2d> &end)
inline virtual void toPolygonMsg(geometry_msgs::Polygon &polygon) override

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:

polygon[out] the polygon message

Protected Functions

inline void calcCentroid()

Private Members

Eigen::Vector2d start_
Eigen::Vector2d end_
Eigen::Vector2d centroid_