Public Member Functions | Protected Member Functions | Private Attributes | List of all members
base_local_planner::TrajectoryCostFunction Class Referenceabstract

Provides an interface for critics of trajectories During each sampling run, a batch of many trajectories will be scored using such a cost function. The prepare method is called before each batch run, and then for each trajectory of the sampling set, score_trajectory may be called. More...

#include <trajectory_cost_function.h>

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

Public Member Functions

double getScale ()
 
virtual bool prepare ()=0
 
virtual double scoreTrajectory (Trajectory &traj)=0
 
void setScale (double scale)
 
virtual ~TrajectoryCostFunction ()
 

Protected Member Functions

 TrajectoryCostFunction (double scale=1.0)
 

Private Attributes

double scale_
 

Detailed Description

Provides an interface for critics of trajectories During each sampling run, a batch of many trajectories will be scored using such a cost function. The prepare method is called before each batch run, and then for each trajectory of the sampling set, score_trajectory may be called.

Definition at line 52 of file trajectory_cost_function.h.

Constructor & Destructor Documentation

virtual base_local_planner::TrajectoryCostFunction::~TrajectoryCostFunction ( )
inlinevirtual

Definition at line 75 of file trajectory_cost_function.h.

base_local_planner::TrajectoryCostFunction::TrajectoryCostFunction ( double  scale = 1.0)
inlineprotected

Definition at line 78 of file trajectory_cost_function.h.

Member Function Documentation

double base_local_planner::TrajectoryCostFunction::getScale ( )
inline

Definition at line 67 of file trajectory_cost_function.h.

virtual bool base_local_planner::TrajectoryCostFunction::prepare ( )
pure virtual

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

Implemented in base_local_planner::MapGridCostFunction, base_local_planner::TwirlingCostFunction, base_local_planner::ObstacleCostFunction, base_local_planner::OscillationCostFunction, and base_local_planner::PreferForwardCostFunction.

virtual double base_local_planner::TrajectoryCostFunction::scoreTrajectory ( Trajectory traj)
pure virtual
void base_local_planner::TrajectoryCostFunction::setScale ( double  scale)
inline

Definition at line 71 of file trajectory_cost_function.h.

Member Data Documentation

double base_local_planner::TrajectoryCostFunction::scale_
private

Definition at line 81 of file trajectory_cost_function.h.


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


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