Public Member Functions | Private Attributes | List of all members
base_local_planner::MapGridCostFunction Class Reference

#include <map_grid_cost_function.h>

Inheritance diagram for base_local_planner::MapGridCostFunction:
Inheritance graph
[legend]

Public Member Functions

double getCellCosts (unsigned int cx, unsigned int cy)
 
 MapGridCostFunction (costmap_2d::Costmap2D *costmap, double xshift=0.0, double yshift=0.0, bool is_local_goal_function=false, CostAggregationType aggregationType=Last)
 
double obstacleCosts ()
 
bool prepare ()
 
double scoreTrajectory (Trajectory &traj)
 
void setStopOnFailure (bool stop_on_failure)
 If true, failures along the path cause the entire path to be rejected. More...
 
void setTargetPoses (std::vector< geometry_msgs::PoseStamped > target_poses)
 
void setXShift (double xshift)
 
void setYShift (double yshift)
 
double unreachableCellCosts ()
 
 ~MapGridCostFunction ()
 
- Public Member Functions inherited from base_local_planner::TrajectoryCostFunction
double getScale ()
 
void setScale (double scale)
 
virtual ~TrajectoryCostFunction ()
 

Private Attributes

CostAggregationType aggregationType_
 
costmap_2d::Costmap2Dcostmap_
 
bool is_local_goal_function_
 
base_local_planner::MapGrid map_
 
bool stop_on_failure_
 
std::vector< geometry_msgs::PoseStamped > target_poses_
 
double xshift_
 xshift and yshift allow scoring for different More...
 
double yshift_
 

Additional Inherited Members

- Protected Member Functions inherited from base_local_planner::TrajectoryCostFunction
 TrajectoryCostFunction (double scale=1.0)
 

Detailed Description

This class provides cost based on a map_grid of a small area of the world. The map_grid covers a the costmap, the costmap containing the information about sensed obstacles. The map_grid is used by setting certain cells to distance 0, and then propagating distances around them, filling up the area reachable around them.

The approach using grid_maps is used for computational efficiency, allowing to score hundreds of trajectories very quickly.

This can be used to favor trajectories which stay on a given path, or which approach a given goal.

Parameters
costmap_rosReference to object giving updates of obstacles around robot
xshiftwhere the scoring point is with respect to robot center pose
yshiftwhere the scoring point is with respect to robot center pose
is_local_goal_function,scoresfor local goal rather than whole path
aggregationTypehow to combine costs along trajectory

Definition at line 73 of file map_grid_cost_function.h.

Constructor & Destructor Documentation

base_local_planner::MapGridCostFunction::MapGridCostFunction ( costmap_2d::Costmap2D costmap,
double  xshift = 0.0,
double  yshift = 0.0,
bool  is_local_goal_function = false,
CostAggregationType  aggregationType = Last 
)

Definition at line 42 of file map_grid_cost_function.cpp.

base_local_planner::MapGridCostFunction::~MapGridCostFunction ( )
inline

Definition at line 81 of file map_grid_cost_function.h.

Member Function Documentation

double base_local_planner::MapGridCostFunction::getCellCosts ( unsigned int  cx,
unsigned int  cy 
)

Definition at line 70 of file map_grid_cost_function.cpp.

double base_local_planner::MapGridCostFunction::obstacleCosts ( )
inline

return a value that indicates cell is in obstacle

Definition at line 106 of file map_grid_cost_function.h.

bool base_local_planner::MapGridCostFunction::prepare ( )
virtual

propagate distances

Implements base_local_planner::TrajectoryCostFunction.

Definition at line 59 of file map_grid_cost_function.cpp.

double base_local_planner::MapGridCostFunction::scoreTrajectory ( Trajectory traj)
virtual

return a score for trajectory traj

Implements base_local_planner::TrajectoryCostFunction.

Definition at line 75 of file map_grid_cost_function.cpp.

void base_local_planner::MapGridCostFunction::setStopOnFailure ( bool  stop_on_failure)
inline

If true, failures along the path cause the entire path to be rejected.

Default is true.

Definition at line 94 of file map_grid_cost_function.h.

void base_local_planner::MapGridCostFunction::setTargetPoses ( std::vector< geometry_msgs::PoseStamped >  target_poses)

set line segments on the grid with distance 0, resets the grid

Definition at line 55 of file map_grid_cost_function.cpp.

void base_local_planner::MapGridCostFunction::setXShift ( double  xshift)
inline

Definition at line 88 of file map_grid_cost_function.h.

void base_local_planner::MapGridCostFunction::setYShift ( double  yshift)
inline

Definition at line 89 of file map_grid_cost_function.h.

double base_local_planner::MapGridCostFunction::unreachableCellCosts ( )
inline

returns a value indicating cell was not reached by wavefront propagation of set cells. (is behind walls, regarding the region covered by grid)

Definition at line 114 of file map_grid_cost_function.h.

Member Data Documentation

CostAggregationType base_local_planner::MapGridCostFunction::aggregationType_
private

Definition at line 126 of file map_grid_cost_function.h.

costmap_2d::Costmap2D* base_local_planner::MapGridCostFunction::costmap_
private

Definition at line 123 of file map_grid_cost_function.h.

bool base_local_planner::MapGridCostFunction::is_local_goal_function_
private

Definition at line 134 of file map_grid_cost_function.h.

base_local_planner::MapGrid base_local_planner::MapGridCostFunction::map_
private

Definition at line 125 of file map_grid_cost_function.h.

bool base_local_planner::MapGridCostFunction::stop_on_failure_
private

Definition at line 135 of file map_grid_cost_function.h.

std::vector<geometry_msgs::PoseStamped> base_local_planner::MapGridCostFunction::target_poses_
private

Definition at line 122 of file map_grid_cost_function.h.

double base_local_planner::MapGridCostFunction::xshift_
private

xshift and yshift allow scoring for different

Definition at line 131 of file map_grid_cost_function.h.

double base_local_planner::MapGridCostFunction::yshift_
private

Definition at line 132 of file map_grid_cost_function.h.


The documentation for this class was generated from the following files:


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Sun Mar 3 2019 03:44:25