Class that approximates the robot with two shifted circles. 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. | |
void | setParameters (double front_offset, double front_radius, double rear_offset, double rear_radius) |
Set parameters of the contour/footprint. | |
TwoCirclesRobotFootprint (double front_offset, double front_radius, double rear_offset, double rear_radius) | |
Default constructor of the abstract obstacle class. | |
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers) const |
Visualize the robot using a markers. | |
virtual | ~TwoCirclesRobotFootprint () |
Virtual destructor. | |
Private Attributes | |
double | front_offset_ |
double | front_radius_ |
double | rear_offset_ |
double | rear_radius_ |
Class that approximates the robot with two shifted circles.
Definition at line 232 of file robot_footprint_model.h.
teb_local_planner::TwoCirclesRobotFootprint::TwoCirclesRobotFootprint | ( | double | front_offset, |
double | front_radius, | ||
double | rear_offset, | ||
double | rear_radius | ||
) | [inline] |
Default constructor of the abstract obstacle class.
front_offset | shift the center of the front circle along the robot orientation starting from the center at the rear axis (in meters) |
front_radius | radius of the front circle |
rear_offset | shift the center of the rear circle along the opposite robot orientation starting from the center at the rear axis (in meters) |
rear_radius | radius of the front circle |
Definition at line 243 of file robot_footprint_model.h.
virtual teb_local_planner::TwoCirclesRobotFootprint::~TwoCirclesRobotFootprint | ( | ) | [inline, virtual] |
Virtual destructor.
Definition at line 249 of file robot_footprint_model.h.
virtual double teb_local_planner::TwoCirclesRobotFootprint::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 267 of file robot_footprint_model.h.
virtual double teb_local_planner::TwoCirclesRobotFootprint::getInscribedRadius | ( | ) | [inline, virtual] |
Compute the inscribed radius of the footprint model.
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 323 of file robot_footprint_model.h.
void teb_local_planner::TwoCirclesRobotFootprint::setParameters | ( | double | front_offset, |
double | front_radius, | ||
double | rear_offset, | ||
double | rear_radius | ||
) | [inline] |
Set parameters of the contour/footprint.
front_offset | shift the center of the front circle along the robot orientation starting from the center at the rear axis (in meters) |
front_radius | radius of the front circle |
rear_offset | shift the center of the rear circle along the opposite robot orientation starting from the center at the rear axis (in meters) |
rear_radius | radius of the front circle |
Definition at line 258 of file robot_footprint_model.h.
virtual void teb_local_planner::TwoCirclesRobotFootprint::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 283 of file robot_footprint_model.h.
double teb_local_planner::TwoCirclesRobotFootprint::front_offset_ [private] |
Definition at line 332 of file robot_footprint_model.h.
double teb_local_planner::TwoCirclesRobotFootprint::front_radius_ [private] |
Definition at line 333 of file robot_footprint_model.h.
double teb_local_planner::TwoCirclesRobotFootprint::rear_offset_ [private] |
Definition at line 334 of file robot_footprint_model.h.
double teb_local_planner::TwoCirclesRobotFootprint::rear_radius_ [private] |
Definition at line 335 of file robot_footprint_model.h.