Class that approximates the robot with a closed polygon.
More...
#include <robot_footprint_model.h>
Class that approximates the robot with a closed polygon.
Definition at line 541 of file robot_footprint_model.h.
teb_local_planner::PolygonRobotFootprint::PolygonRobotFootprint |
( |
const Point2dContainer & |
vertices | ) |
|
|
inline |
Default constructor of the abstract obstacle class.
- Parameters
-
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 551 of file robot_footprint_model.h.
virtual teb_local_planner::PolygonRobotFootprint::~PolygonRobotFootprint |
( |
| ) |
|
|
inlinevirtual |
virtual double teb_local_planner::PolygonRobotFootprint::calculateDistance |
( |
const PoseSE2 & |
current_pose, |
|
|
const Obstacle * |
obstacle |
|
) |
| const |
|
inlinevirtual |
virtual double teb_local_planner::PolygonRobotFootprint::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 584 of file robot_footprint_model.h.
virtual double teb_local_planner::PolygonRobotFootprint::getInscribedRadius |
( |
| ) |
|
|
inlinevirtual |
void teb_local_planner::PolygonRobotFootprint::setVertices |
( |
const Point2dContainer & |
vertices | ) |
|
|
inline |
Set vertices of the contour/footprint.
- Parameters
-
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 562 of file robot_footprint_model.h.
void teb_local_planner::PolygonRobotFootprint::transformToWorld |
( |
const PoseSE2 & |
current_pose, |
|
|
Point2dContainer & |
polygon_world |
|
) |
| const |
|
inlineprivate |
Transforms a polygon to the world frame manually.
- Parameters
-
| current_pose | Current robot pose |
[out] | polygon_world | polygon in the world frame |
Definition at line 663 of file robot_footprint_model.h.
virtual void teb_local_planner::PolygonRobotFootprint::visualizeRobot |
( |
const PoseSE2 & |
current_pose, |
|
|
std::vector< visualization_msgs::Marker > & |
markers, |
|
|
const std_msgs::ColorRGBA & |
color |
|
) |
| 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 |
| color | Color of the footprint |
Reimplemented from teb_local_planner::BaseRobotFootprintModel.
Definition at line 600 of file robot_footprint_model.h.
The documentation for this class was generated from the following file: