An interface the trajectory controller uses to interact with the world regardless of the underlying world model.
More...
#include <world_model.h>
|
virtual double | footprintCost (const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0 |
| Subclass will implement this method to check a footprint at a given position and orientation for legality in the world. More...
|
|
double | footprintCost (double x, double y, double theta, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0) |
|
double | footprintCost (const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius, double extra) |
| Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid. More...
|
|
virtual | ~WorldModel () |
| Subclass will implement a destructor. More...
|
|
An interface the trajectory controller uses to interact with the world regardless of the underlying world model.
Definition at line 52 of file world_model.h.
virtual base_local_planner::WorldModel::~WorldModel |
( |
| ) |
|
|
inlinevirtual |
Subclass will implement a destructor.
Definition at line 104 of file world_model.h.
base_local_planner::WorldModel::WorldModel |
( |
| ) |
|
|
inlineprotected |
virtual double base_local_planner::WorldModel::footprintCost |
( |
const geometry_msgs::Point & |
position, |
|
|
const std::vector< geometry_msgs::Point > & |
footprint, |
|
|
double |
inscribed_radius, |
|
|
double |
circumscribed_radius |
|
) |
| |
|
pure virtual |
Subclass will implement this method to check a footprint at a given position and orientation for legality in the world.
- Parameters
-
position | The position of the robot in world coordinates |
footprint | The specification of the footprint of the robot in world coordinates |
inscribed_radius | The radius of the inscribed circle of the robot |
circumscribed_radius | The radius of the circumscribed circle of the robot |
- Returns
- Positive if all the points lie outside the footprint, negative otherwise
Implemented in base_local_planner::PointGrid, base_local_planner::VoxelGridModel, and base_local_planner::CostmapModel.
double base_local_planner::WorldModel::footprintCost |
( |
double |
x, |
|
|
double |
y, |
|
|
double |
theta, |
|
|
const std::vector< geometry_msgs::Point > & |
footprint_spec, |
|
|
double |
inscribed_radius = 0.0 , |
|
|
double |
circumscribed_radius = 0.0 |
|
) |
| |
|
inline |
double base_local_planner::WorldModel::footprintCost |
( |
const geometry_msgs::Point & |
position, |
|
|
const std::vector< geometry_msgs::Point > & |
footprint, |
|
|
double |
inscribed_radius, |
|
|
double |
circumscribed_radius, |
|
|
double |
extra |
|
) |
| |
|
inline |
Checks if any obstacles in the costmap lie inside a convex footprint that is rasterized into the grid.
- Parameters
-
position | The position of the robot in world coordinates |
footprint | The specification of the footprint of the robot in world coordinates |
inscribed_radius | The radius of the inscribed circle of the robot |
circumscribed_radius | The radius of the circumscribed circle of the robot |
- Returns
- Positive if all the points lie outside the footprint, negative otherwise
Definition at line 96 of file world_model.h.
The documentation for this class was generated from the following file: