Class CircularObstacle
Defined in File obstacles.h
Inheritance Relationships
Base Type
public hateb_local_planner::Obstacle(Class Obstacle)
Class Documentation
-
class CircularObstacle : public hateb_local_planner::Obstacle
Implements a 2D circular obstacle (point obstacle plus radius)
Public Functions
-
inline CircularObstacle()
Default constructor of the circular obstacle class.
-
inline CircularObstacle(const Eigen::Ref<const Eigen::Vector2d> &position, double radius)
Construct CircularObstacle using a 2d center position vector and radius.
- Parameters:
position – 2d position that defines the current obstacle position
radius – radius of the obstacle
-
inline CircularObstacle(double x, double y, double radius)
Construct CircularObstacle using x- and y-center-coordinates and radius.
- Parameters:
x – x-coordinate
y – y-coordinate
radius – radius of the obstacle
-
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:
trueif 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:
trueif 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 void predictCentroidConstantVelocity(double t, Eigen::Ref<Eigen::Vector2d> position) const override
Predict position of the centroid assuming a constant velocity model.
- Parameters:
t – [in] time in seconds for the prediction (t>=0)
position – [out] predicted 2d position of the centroid
-
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 &position() const
Return the current position of the obstacle (read-only)
-
inline Eigen::Vector2d &position()
Return the current position of the obstacle.
-
inline double &x()
Return the current x-coordinate of the obstacle.
-
inline const double &x() const
Return the current y-coordinate of the obstacle (read-only)
-
inline double &y()
Return the current x-coordinate of the obstacle.
-
inline const double &y() const
Return the current y-coordinate of the obstacle (read-only)
-
inline double &radius()
Return the current radius of the obstacle.
-
inline const double &radius() const
Return the current radius of the obstacle.
-
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
-
inline void setCentroid(double x, double y)
Protected Attributes
-
Eigen::Vector2d pos_
Store the center position of the CircularObstacle.
-
double radius_ = 0.0
Radius of the obstacle.
-
inline CircularObstacle()