Class that defines the a robot of circular shape. More...
#include <robot_footprint_model.h>
Public Member Functions | |
virtual double | calculateDistance (const PoseSE2 ¤t_pose, const Obstacle *obstacle) const |
Calculate the distance between the robot and an obstacle. More... | |
CircularRobotFootprint (double radius) | |
Default constructor of the abstract obstacle class. More... | |
virtual double | estimateSpatioTemporalDistance (const PoseSE2 ¤t_pose, const Obstacle *obstacle, double t) const |
Estimate the distance between the robot and the predicted location of an obstacle at time t. More... | |
virtual double | getInscribedRadius () |
Compute the inscribed radius of the footprint model. More... | |
void | setRadius (double radius) |
Set radius of the circular robot. More... | |
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers, const std_msgs::ColorRGBA &color) const |
Visualize the robot using a markers. More... | |
virtual | ~CircularRobotFootprint () |
Virtual destructor. More... | |
Public Member Functions inherited from teb_local_planner::BaseRobotFootprintModel | |
BaseRobotFootprintModel () | |
Default constructor of the abstract obstacle class. More... | |
virtual | ~BaseRobotFootprintModel () |
Virtual destructor. More... | |
Private Attributes | |
double | radius_ |
Class that defines the a robot of circular shape.
Definition at line 184 of file robot_footprint_model.h.
|
inline |
Default constructor of the abstract obstacle class.
radius | radius of the robot |
Definition at line 192 of file robot_footprint_model.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 197 of file robot_footprint_model.h.
|
inlinevirtual |
Calculate the distance between the robot and an obstacle.
current_pose | Current robot pose |
obstacle | Pointer to the obstacle |
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 211 of file robot_footprint_model.h.
|
inlinevirtual |
Estimate the distance between the robot and the predicted location of an obstacle at time t.
current_pose | robot 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 |
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 223 of file robot_footprint_model.h.
|
inlinevirtual |
Compute the inscribed radius of the footprint model.
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 252 of file robot_footprint_model.h.
|
inline |
Set radius of the circular robot.
radius | radius of the robot |
Definition at line 203 of file robot_footprint_model.h.
|
inlinevirtual |
Visualize the robot 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.
current_pose | Current robot pose | |
[out] | markers | container of marker messages describing the robot shape |
color | Color of the footprint |
Reimplemented from teb_local_planner::BaseRobotFootprintModel.
Definition at line 237 of file robot_footprint_model.h.
|
private |
Definition at line 256 of file robot_footprint_model.h.