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. | |
CircularRobotFootprint (double radius) | |
Default constructor of the abstract obstacle class. | |
void | setRadius (double radius) |
Set radius of the circular robot. | |
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers) const |
Visualize the robot using a markers. | |
virtual | ~CircularRobotFootprint () |
Virtual destructor. | |
Private Attributes | |
double | radius_ |
Class that defines the a robot of circular shape.
Definition at line 149 of file robot_footprint_model.h.
teb_local_planner::CircularRobotFootprint::CircularRobotFootprint | ( | double | radius | ) | [inline] |
Default constructor of the abstract obstacle class.
radius | radius of the robot |
Definition at line 157 of file robot_footprint_model.h.
virtual teb_local_planner::CircularRobotFootprint::~CircularRobotFootprint | ( | ) | [inline, virtual] |
Virtual destructor.
Definition at line 162 of file robot_footprint_model.h.
virtual double teb_local_planner::CircularRobotFootprint::calculateDistance | ( | const PoseSE2 & | current_pose, |
const Obstacle * | obstacle | ||
) | const [inline, virtual] |
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 176 of file robot_footprint_model.h.
void teb_local_planner::CircularRobotFootprint::setRadius | ( | double | radius | ) | [inline] |
Set radius of the circular robot.
radius | radius of the robot |
Definition at line 168 of file robot_footprint_model.h.
virtual void teb_local_planner::CircularRobotFootprint::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 from teb_local_planner::BaseRobotFootprintModel.
Definition at line 189 of file robot_footprint_model.h.
double teb_local_planner::CircularRobotFootprint::radius_ [private] |
Definition at line 205 of file robot_footprint_model.h.