Abstract class that defines the interface for robot footprint/contour models. More...
#include <robot_footprint_model.h>
Public Member Functions | |
BaseRobotFootprintModel () | |
Default constructor of the abstract obstacle class. | |
virtual double | calculateDistance (const PoseSE2 ¤t_pose, const Obstacle *obstacle) const =0 |
Calculate the distance between the robot and an obstacle. | |
virtual double | getInscribedRadius ()=0 |
Compute the inscribed radius of the footprint model. | |
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers) const |
Visualize the robot using a markers. | |
virtual | ~BaseRobotFootprintModel () |
Virtual destructor. |
Abstract class that defines the interface for robot footprint/contour models.
The robot 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.
Definition at line 58 of file robot_footprint_model.h.
Default constructor of the abstract obstacle class.
Definition at line 65 of file robot_footprint_model.h.
virtual teb_local_planner::BaseRobotFootprintModel::~BaseRobotFootprintModel | ( | ) | [inline, virtual] |
Virtual destructor.
Definition at line 72 of file robot_footprint_model.h.
virtual double teb_local_planner::BaseRobotFootprintModel::calculateDistance | ( | const PoseSE2 & | current_pose, |
const Obstacle * | obstacle | ||
) | const [pure virtual] |
Calculate the distance between the robot and an obstacle.
current_pose | Current robot pose |
obstacle | Pointer to the obstacle |
Implemented in teb_local_planner::PolygonRobotFootprint, teb_local_planner::LineRobotFootprint, teb_local_planner::TwoCirclesRobotFootprint, teb_local_planner::CircularRobotFootprint, and teb_local_planner::PointRobotFootprint.
virtual double teb_local_planner::BaseRobotFootprintModel::getInscribedRadius | ( | ) | [pure virtual] |
Compute the inscribed radius of the footprint model.
Implemented in teb_local_planner::PolygonRobotFootprint, teb_local_planner::LineRobotFootprint, teb_local_planner::TwoCirclesRobotFootprint, teb_local_planner::CircularRobotFootprint, and teb_local_planner::PointRobotFootprint.
virtual void teb_local_planner::BaseRobotFootprintModel::visualizeRobot | ( | const PoseSE2 & | current_pose, |
std::vector< visualization_msgs::Marker > & | markers | ||
) | const [inline, virtual] |
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 |
Reimplemented in teb_local_planner::PolygonRobotFootprint, teb_local_planner::LineRobotFootprint, teb_local_planner::TwoCirclesRobotFootprint, and teb_local_planner::CircularRobotFootprint.
Definition at line 93 of file robot_footprint_model.h.