Class Obstacle
Defined in File obstacles.h
Inheritance Relationships
Derived Types
public hateb_local_planner::CircularObstacle(Class CircularObstacle)public hateb_local_planner::LineObstacle(Class LineObstacle)public hateb_local_planner::PointObstacle(Class PointObstacle)public hateb_local_planner::PolygonObstacle(Class PolygonObstacle)
Class Documentation
-
class Obstacle
Abstract class that defines the interface for modelling obstacles.
Subclassed by hateb_local_planner::CircularObstacle, hateb_local_planner::LineObstacle, hateb_local_planner::PointObstacle, hateb_local_planner::PolygonObstacle
Helper Functions
-
bool dynamic_ = {}
Store flag if obstacle is dynamic (resp. a moving obstacle)
-
bool human_ = {}
-
Eigen::Vector2d centroid_velocity_
Store the corresponding velocity (vx, vy) of the centroid (zero, if _dynamic is
true)
-
virtual void toPolygonMsg(geometry_msgs::Polygon &polygon) = 0
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 virtual void toTwistWithCovarianceMsg(geometry_msgs::TwistWithCovariance &twistWithCovariance)
Centroid coordinates (abstract, obstacle type depending)
-
virtual const Eigen::Vector2d &getCentroid() const = 0
Get centroid coordinates of the obstacle.
- Returns:
Eigen::Vector2d containing the centroid
-
virtual std::complex<double> getCentroidCplx() const = 0
Get centroid coordinates of the obstacle as complex number.
- Returns:
std::complex containing the centroid coordinate
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.
- 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
-
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)- 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
-
virtual double getMinimumDistance(const Eigen::Vector2d &position) const = 0
Get the minimum euclidean distance to the obstacle (point as reference)
- Parameters:
position – 2d reference position
- Returns:
The nearest possible distance to the obstacle
-
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)
- 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
-
virtual double getMinimumDistance(const Point2dContainer &polygon) const = 0
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 = 0
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
-
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)
- 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
-
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)
- 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
-
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)
- 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
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 bool isDynamic() const
Check if the obstacle is a moving with a (non-zero) velocity.
- Returns:
trueif the obstacle is not marked as static,falseotherwise
-
inline bool isHuman() const
returns true if the obstacle is marked as invisible human
-
inline void setHuman()
-
inline void setCentroidVelocity(const Eigen::Ref<const Eigen::Vector2d> &vel)
Set the 2d velocity (vx, vy) of the obstacle w.r.t to the centroid.
Remark
Setting the velocity using this function marks the obstacle as dynamic (
See also
- Parameters:
vel – 2D vector containing the velocities of the centroid in x and y directions
-
inline 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.
Remark
Setting the velocity using this function marks the obstacle as dynamic (
See also
- Parameters:
velocity – geometry_msgs::TwistWithCovariance containing the velocity of the obstacle
orientation – geometry_msgs::QuaternionStamped containing the orientation of the obstacle
-
inline void setCentroidVelocity(const geometry_msgs::TwistWithCovariance &velocity, const geometry_msgs::QuaternionStamped &orientation)
-
inline const Eigen::Vector2d &getCentroidVelocity() const
Get the obstacle velocity (vx, vy) (w.r.t. to the centroid)
- Returns:
2D vector containing the velocities of the centroid in x and y directions
-
bool dynamic_ = {}