Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B > Class Template Referenceabstract

#include <value_function.h>

Inheritance diagram for fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >:
Inheritance graph
[legend]

Public Member Functions

const RelativeDynamics< TS, TC, PS, PC > & GetRelativeDynamics () const
 
virtual std::unique_ptr< RelativeState< TS, PS > > Gradient (const TS &tracker_x, const PS &planner_x) const =0
 
bool Initialize (const ros::NodeHandle &n)
 
TC OptimalControl (const TS &tracker_x, const PS &planner_x) const
 
const PD & PlannerDynamics () const
 
virtual double Priority (const TS &tracker_x, const PS &planner_x) const =0
 
const TD & TrackerDynamics () const
 
const B & TrackingBound () const
 
virtual double Value (const TS &tracker_x, const PS &planner_x) const =0
 
virtual ~ValueFunction ()
 

Protected Member Functions

virtual bool LoadParameters (const ros::NodeHandle &n)
 
virtual bool RegisterCallbacks (const ros::NodeHandle &n)
 
 ValueFunction ()
 

Protected Attributes

bound_
 
bool initialized_
 
std::string name_
 
PD planner_dynamics_
 
std::unique_ptr< RelativeDynamics< TS, TC, PS, PC > > relative_dynamics_
 
TD tracker_dynamics_
 

Additional Inherited Members

- Private Member Functions inherited from fastrack::Uncopyable
 Uncopyable ()
 
virtual ~Uncopyable ()
 

Detailed Description

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
class fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >

Definition at line 65 of file value_function.h.

Constructor & Destructor Documentation

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
virtual fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::~ValueFunction ( )
inlinevirtual

Definition at line 67 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::ValueFunction ( )
inlineexplicitprotected

Definition at line 123 of file value_function.h.

Member Function Documentation

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
const RelativeDynamics<TS, TC, PS, PC>& fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::GetRelativeDynamics ( ) const
inline

Definition at line 109 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
virtual std::unique_ptr<RelativeState<TS, PS> > fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::Gradient ( const TS &  tracker_x,
const PS &  planner_x 
) const
pure virtual
template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
bool fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::Initialize ( const ros::NodeHandle &  n)
inline

Definition at line 70 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
virtual bool fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::LoadParameters ( const ros::NodeHandle &  n)
inlineprotectedvirtual
template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
TC fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::OptimalControl ( const TS &  tracker_x,
const PS &  planner_x 
) const
inline

Definition at line 93 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
const PD& fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::PlannerDynamics ( ) const
inline

Definition at line 108 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
virtual double fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::Priority ( const TS &  tracker_x,
const PS &  planner_x 
) const
pure virtual
template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
virtual bool fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::RegisterCallbacks ( const ros::NodeHandle &  n)
inlineprotectedvirtual
template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
const TD& fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::TrackerDynamics ( ) const
inline

Definition at line 107 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
const B& fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::TrackingBound ( ) const
inline

Definition at line 106 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
virtual double fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::Value ( const TS &  tracker_x,
const PS &  planner_x 
) const
pure virtual

Member Data Documentation

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
B fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::bound_
protected

Definition at line 138 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
bool fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::initialized_
protected

Definition at line 142 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
std::string fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::name_
protected

Definition at line 141 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
PD fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::planner_dynamics_
protected

Definition at line 134 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
std::unique_ptr<RelativeDynamics<TS, TC, PS, PC> > fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::relative_dynamics_
protected

Definition at line 135 of file value_function.h.

template<typename TS, typename TC, typename TD, typename PS, typename PC, typename PD, typename B>
TD fastrack::value::ValueFunction< TS, TC, TD, PS, PC, PD, B >::tracker_dynamics_
protected

Definition at line 133 of file value_function.h.


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


fastrack
Author(s): David Fridovich-Keil
autogenerated on Mon Aug 3 2020 21:28:37