Class that approximates the robot with two shifted circles.
More...
#include <robot_footprint_model.h>
|
virtual double | calculateDistance (const PoseSE2 ¤t_pose, const Obstacle *obstacle) const |
| Calculate the distance between the robot and an obstacle. 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 | setParameters (double front_offset, double front_radius, double rear_offset, double rear_radius) |
| Set parameters of the contour/footprint. More...
|
|
| TwoCirclesRobotFootprint (double front_offset, double front_radius, double rear_offset, double rear_radius) |
| Default constructor of the abstract obstacle class. More...
|
|
virtual void | visualizeRobot (const PoseSE2 ¤t_pose, std::vector< visualization_msgs::Marker > &markers) const |
| Visualize the robot using a markers. More...
|
|
virtual | ~TwoCirclesRobotFootprint () |
| Virtual destructor. More...
|
|
Class that approximates the robot with two shifted circles.
Definition at line 265 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.
- Parameters
-
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 276 of file robot_footprint_model.h.
virtual teb_local_planner::TwoCirclesRobotFootprint::~TwoCirclesRobotFootprint |
( |
| ) |
|
|
inlinevirtual |
virtual double teb_local_planner::TwoCirclesRobotFootprint::calculateDistance |
( |
const PoseSE2 & |
current_pose, |
|
|
const Obstacle * |
obstacle |
|
) |
| const |
|
inlinevirtual |
virtual double teb_local_planner::TwoCirclesRobotFootprint::estimateSpatioTemporalDistance |
( |
const PoseSE2 & |
current_pose, |
|
|
const Obstacle * |
obstacle, |
|
|
double |
t |
|
) |
| const |
|
inlinevirtual |
Estimate the distance between the robot and the predicted location of an obstacle at time t.
- Parameters
-
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 |
- Returns
- Euclidean distance to the robot
Implements teb_local_planner::BaseRobotFootprintModel.
Definition at line 315 of file robot_footprint_model.h.
virtual double teb_local_planner::TwoCirclesRobotFootprint::getInscribedRadius |
( |
| ) |
|
|
inlinevirtual |
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.
- Parameters
-
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 291 of file robot_footprint_model.h.
virtual void teb_local_planner::TwoCirclesRobotFootprint::visualizeRobot |
( |
const PoseSE2 & |
current_pose, |
|
|
std::vector< visualization_msgs::Marker > & |
markers |
|
) |
| const |
|
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.
- Parameters
-
| current_pose | Current robot pose |
[out] | markers | container of marker messages describing the robot shape |
Reimplemented from teb_local_planner::BaseRobotFootprintModel.
Definition at line 331 of file robot_footprint_model.h.
double teb_local_planner::TwoCirclesRobotFootprint::front_offset_ |
|
private |
double teb_local_planner::TwoCirclesRobotFootprint::front_radius_ |
|
private |
double teb_local_planner::TwoCirclesRobotFootprint::rear_offset_ |
|
private |
double teb_local_planner::TwoCirclesRobotFootprint::rear_radius_ |
|
private |
The documentation for this class was generated from the following file: