Class BaseFootprintModel
Defined in File footprint_model.h
Inheritance Relationships
Derived Types
public hateb_local_planner::CircularFootprint(Class CircularFootprint)public hateb_local_planner::LineFootprint(Class LineFootprint)public hateb_local_planner::PointFootprint(Class PointFootprint)public hateb_local_planner::PolygonFootprint(Class PolygonFootprint)public hateb_local_planner::TwoCirclesFootprint(Class TwoCirclesFootprint)
Class Documentation
-
class BaseFootprintModel
Abstract class that defines the interface for footprint/contour models.
The robot/human model class is currently used in optimization only, since taking the navigation stack footprint into account might be inefficient. The footprint is only used for checking feasibility.
Subclassed by hateb_local_planner::CircularFootprint, hateb_local_planner::LineFootprint, hateb_local_planner::PointFootprint, hateb_local_planner::PolygonFootprint, hateb_local_planner::TwoCirclesFootprint
Public Functions
-
BaseFootprintModel() = default
Default constructor of the abstract obstacle class.
-
virtual ~BaseFootprintModel() = default
Virtual destructor.
-
virtual double calculateDistance(const PoseSE2 ¤t_pose, const Obstacle *obstacle) const = 0
Calculate the distance between the robot/human and an obstacle.
- Parameters:
current_pose – Current robot/human pose
obstacle – Pointer to the obstacle
- Returns:
Euclidean distance to the robot/human
-
virtual double estimateSpatioTemporalDistance(const PoseSE2 ¤t_pose, const Obstacle *obstacle, double t) const = 0
Estimate the distance between the robot/human and the predicted location of an obstacle at time t.
- Parameters:
current_pose – robot/human pose, from which the distance to the obstacle is estimated
obstacle – Pointer to the dynamic obstacle (constant velocity model is assumed)
t – time, for which the predicted distance to the obstacle is calculated
- Returns:
Euclidean distance to the robot/human
-
inline virtual void visualizeModel(const PoseSE2 ¤t_pose, std::vector<visualization_msgs::Marker> &markers, const std_msgs::ColorRGBA &color) const
Visualize the robot/human using a markers.
Fill a marker message with all necessary information (type, pose, scale and color). The header, namespace, id and marker lifetime will be overwritten.
- Parameters:
current_pose – Current robot/human pose
markers – [out] container of marker messages describing the robot/human shape
color – Color of the footprint
-
virtual double getInscribedRadius() = 0
Compute the inscribed radius of the footprint model.
- Returns:
inscribed radius
-
virtual double getCircumscribedRadius() const = 0
Compute the circumscribed radius of the footprint model.
- Returns:
circumscribed radius
-
BaseFootprintModel() = default