Class PolygonObstacle

Inheritance Relationships

Base Type

Class Documentation

class PolygonObstacle : public hateb_local_planner::Obstacle

Implements a polygon obstacle with an arbitrary number of vertices.

If the polygon has only 2 vertices, than it is considered as a line, otherwise the polygon will always be closed (a connection between the first and the last vertex is included automatically).

Define the polygon

inline const Point2dContainer &vertices() const

Access vertices container (read-only)

inline Point2dContainer &vertices()

Access vertices container.

inline void pushBackVertex(const Eigen::Ref<const Eigen::Vector2d> &vertex)

Add a vertex to the polygon (edge-point)

Remark

You do not need to close the polygon (do not repeat the first vertex)

Warning

Do not forget to call finalizePolygon() after adding all vertices

Parameters:

vertex – 2D point defining a new polygon edge

inline void pushBackVertex(double x, double y)

Add a vertex to the polygon (edge-point)

Remark

You do not need to close the polygon (do not repeat the first vertex)

Warning

Do not forget to call finalizePolygon() after adding all vertices

Parameters:
  • x – x-coordinate of the new vertex

  • y – y-coordinate of the new vertex

inline void finalizePolygon()

Call finalizePolygon after the polygon is created with the help of pushBackVertex() methods.

inline void clearVertices()

Clear all vertices (Afterwards the polygon is not valid anymore)

inline int noVertices() const

Get the number of vertices defining the polygon (the first vertex is counted once)

Public Functions

inline PolygonObstacle()

Default constructor of the polygon obstacle class.

inline explicit PolygonObstacle(Point2dContainer vertices)

Construct polygon obstacle with a list of vertices.

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

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)

Remark

we ignore min_dist here

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

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 void predictVertices(double t, Point2dContainer &pred_vertices) const
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

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

void fixPolygonClosure()

Check if the current polygon contains the first vertex twice (as start and end) and in that case erase the last redundant one.

void calcCentroid()

Compute the centroid of the polygon (called inside finalizePolygon())

Protected Attributes

Point2dContainer vertices_

Store vertices defining the polygon (.

See also

pushBackVertex)

Eigen::Vector2d centroid_

Store the centroid coordinates of the polygon (.

See also

calcCentroid)

bool finalized_

Flat that keeps track if the polygon was finalized after adding all vertices.