Class that approximates the robot with a closed polygon. 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. | |
virtual double | getInscribedRadius () |
Compute the inscribed radius of the footprint model. | |
PolygonRobotFootprint (const Point2dContainer &vertices) | |
Default constructor of the abstract obstacle class. | |
void | setVertices (const Point2dContainer &vertices) |
Set vertices of the contour/footprint. | |
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers) const |
Visualize the robot using a markers. | |
virtual | ~PolygonRobotFootprint () |
Virtual destructor. | |
Private Attributes | |
Point2dContainer | vertices_ |
Class that approximates the robot with a closed polygon.
Definition at line 479 of file robot_footprint_model.h.
teb_local_planner::PolygonRobotFootprint::PolygonRobotFootprint | ( | const Point2dContainer & | vertices | ) | [inline] |
Default constructor of the abstract obstacle class.
vertices | footprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end) |
Definition at line 489 of file robot_footprint_model.h.
virtual teb_local_planner::PolygonRobotFootprint::~PolygonRobotFootprint | ( | ) | [inline, virtual] |
Virtual destructor.
Definition at line 494 of file robot_footprint_model.h.
virtual double teb_local_planner::PolygonRobotFootprint::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 508 of file robot_footprint_model.h.
virtual double teb_local_planner::PolygonRobotFootprint::getInscribedRadius | ( | ) | [inline, virtual] |
Compute the inscribed radius of the footprint model.
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 570 of file robot_footprint_model.h.
void teb_local_planner::PolygonRobotFootprint::setVertices | ( | const Point2dContainer & | vertices | ) | [inline] |
Set vertices of the contour/footprint.
vertices | footprint vertices (only x and y) around the robot center (0,0) (do not repeat the first and last vertex at the end) |
Definition at line 500 of file robot_footprint_model.h.
virtual void teb_local_planner::PolygonRobotFootprint::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 530 of file robot_footprint_model.h.
Definition at line 594 of file robot_footprint_model.h.