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

Uses costmap 2d to assign negative costs if robot footprint in trajectory crosses a cell in which this velocity is not allowed. More...

#include <occupancy_velocity_cost_function.h>

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

Public Member Functions

 OccupancyVelocityCostFunction (costmap_2d::Costmap2D *costmap)
 
bool prepare ()
 
double scoreTrajectory (Trajectory &traj)
 
void setFootprint (const std::vector< geometry_msgs::Point > &footprint_spec)
 
void setParams (double max_trans_vel)
 
 ~OccupancyVelocityCostFunction ()
 
- Public Member Functions inherited from base_local_planner::TrajectoryCostFunction
double getScale ()
 
void setScale (double scale)
 
virtual ~TrajectoryCostFunction ()
 

Private Attributes

costmap_2d::Costmap2Dcostmap_
 
std::vector< geometry_msgs::Point > footprint_spec_
 
double max_trans_vel_
 
base_local_planner::WorldModelworld_model_
 

Additional Inherited Members

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

Detailed Description

Uses costmap 2d to assign negative costs if robot footprint in trajectory crosses a cell in which this velocity is not allowed.

class OccupancyVelocityCostFunction

Definition at line 21 of file occupancy_velocity_cost_function.h.

Constructor & Destructor Documentation

◆ OccupancyVelocityCostFunction()

base_local_planner::OccupancyVelocityCostFunction::OccupancyVelocityCostFunction ( costmap_2d::Costmap2D costmap)

Definition at line 14 of file occupancy_velocity_cost_function.cpp.

◆ ~OccupancyVelocityCostFunction()

base_local_planner::OccupancyVelocityCostFunction::~OccupancyVelocityCostFunction ( )

Definition at line 22 of file occupancy_velocity_cost_function.cpp.

Member Function Documentation

◆ prepare()

bool base_local_planner::OccupancyVelocityCostFunction::prepare ( )
inlinevirtual

General updating of context values if required. Subclasses may overwrite. Return false in case there is any error.

Implements base_local_planner::TrajectoryCostFunction.

Definition at line 29 of file occupancy_velocity_cost_function.h.

◆ scoreTrajectory()

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

return a score for trajectory traj

Implements base_local_planner::TrajectoryCostFunction.

Definition at line 30 of file occupancy_velocity_cost_function.cpp.

◆ setFootprint()

void base_local_planner::OccupancyVelocityCostFunction::setFootprint ( const std::vector< geometry_msgs::Point > &  footprint_spec)
inline

Definition at line 33 of file occupancy_velocity_cost_function.h.

◆ setParams()

void base_local_planner::OccupancyVelocityCostFunction::setParams ( double  max_trans_vel)
inline

Definition at line 32 of file occupancy_velocity_cost_function.h.

Member Data Documentation

◆ costmap_

costmap_2d::Costmap2D* base_local_planner::OccupancyVelocityCostFunction::costmap_
private

Definition at line 36 of file occupancy_velocity_cost_function.h.

◆ footprint_spec_

std::vector<geometry_msgs::Point> base_local_planner::OccupancyVelocityCostFunction::footprint_spec_
private

Definition at line 37 of file occupancy_velocity_cost_function.h.

◆ max_trans_vel_

double base_local_planner::OccupancyVelocityCostFunction::max_trans_vel_
private

Definition at line 39 of file occupancy_velocity_cost_function.h.

◆ world_model_

base_local_planner::WorldModel* base_local_planner::OccupancyVelocityCostFunction::world_model_
private

Definition at line 38 of file occupancy_velocity_cost_function.h.


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