Class PointFootprint
Defined in File footprint_model.h
Inheritance Relationships
Base Type
public hateb_local_planner::BaseFootprintModel(Class BaseFootprintModel)
Class Documentation
-
class PointFootprint : public hateb_local_planner::BaseFootprintModel
Public Functions
-
PointFootprint() = default
Default constructor of the abstract obstacle class.
-
inline explicit PointFootprint(const double min_obstacle_dist)
Default constructor of the abstract obstacle class.
- Parameters:
min_obstacle_dist – Minimum obstacle distance
-
~PointFootprint() override = default
Virtual destructor.
-
inline virtual double calculateDistance(const PoseSE2 ¤t_pose, const Obstacle *obstacle) const override
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
-
inline virtual double estimateSpatioTemporalDistance(const PoseSE2 ¤t_pose, const Obstacle *obstacle, double t) const override
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 double getInscribedRadius() override
Compute the inscribed radius of the footprint model.
- Returns:
inscribed radius
-
inline virtual double getCircumscribedRadius() const override
Compute the circumscribed radius of the footprint model.
- Returns:
circumscribed radius
-
inline virtual void visualizeModel(const PoseSE2 ¤t_pose, std::vector<visualization_msgs::Marker> &markers, const std_msgs::ColorRGBA &color) const override
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
Private Members
-
const double min_obstacle_dist_ = 0.0
-
PointFootprint() = default