#include <TrajectoryModule.hpp>

Public Member Functions | |
| virtual void | destroy ()=0 | 
| virtual void | didTurnInactive ()=0 | 
| std::string | getName () const | 
| int | getPriority () const | 
| TrajModulePosType | getType () const | 
| virtual void | initialize ()=0 | 
| bool | isActive () const | 
| void | setActive () | 
| void | setInactive () | 
| virtual bool | trajectoryStep (const TKState ¤tState, TKTrajectory &trajInput)=0 | 
| virtual void | willTurnActive ()=0 | 
| virtual | ~TrajectoryModule () | 
Protected Member Functions | |
| TrajectoryModule (const std::string &name_, TrajModulePosType type_, int priority_) | |
Protected Attributes | |
| std::string | name | 
| int | priority | 
| TrajectoryProcessorController & | tpController | 
| TrajModulePosType | type | 
Private Attributes | |
| bool | active | 
Definition at line 23 of file TrajectoryModule.hpp.
| TELEKYB_NAMESPACE::TrajectoryModule::TrajectoryModule | ( | const std::string & | name_, | 
| TrajModulePosType | type_, | ||
| int | priority_ | ||
| ) |  [protected] | 
        
Definition at line 14 of file TrajectoryModule.cpp.
| TELEKYB_NAMESPACE::TrajectoryModule::~TrajectoryModule | ( | ) |  [virtual] | 
        
Definition at line 22 of file TrajectoryModule.cpp.
| virtual void TELEKYB_NAMESPACE::TrajectoryModule::destroy | ( | ) |  [pure virtual] | 
        
| virtual void TELEKYB_NAMESPACE::TrajectoryModule::didTurnInactive | ( | ) |  [pure virtual] | 
        
| std::string TELEKYB_NAMESPACE::TrajectoryModule::getName | ( | ) | const | 
Definition at line 32 of file TrajectoryModule.cpp.
| int TELEKYB_NAMESPACE::TrajectoryModule::getPriority | ( | ) | const | 
Definition at line 36 of file TrajectoryModule.cpp.
| TrajModulePosType TELEKYB_NAMESPACE::TrajectoryModule::getType | ( | ) | const | 
Definition at line 27 of file TrajectoryModule.cpp.
| virtual void TELEKYB_NAMESPACE::TrajectoryModule::initialize | ( | ) |  [pure virtual] | 
        
| bool TELEKYB_NAMESPACE::TrajectoryModule::isActive | ( | ) | const | 
Definition at line 41 of file TrajectoryModule.cpp.
Definition at line 45 of file TrajectoryModule.cpp.
Definition at line 54 of file TrajectoryModule.cpp.
| virtual bool TELEKYB_NAMESPACE::TrajectoryModule::trajectoryStep | ( | const TKState & | currentState, | 
| TKTrajectory & | trajInput | ||
| ) |  [pure virtual] | 
        
| virtual void TELEKYB_NAMESPACE::TrajectoryModule::willTurnActive | ( | ) |  [pure virtual] | 
        
bool TELEKYB_NAMESPACE::TrajectoryModule::active [private] | 
        
Definition at line 26 of file TrajectoryModule.hpp.
std::string TELEKYB_NAMESPACE::TrajectoryModule::name [protected] | 
        
Definition at line 32 of file TrajectoryModule.hpp.
int TELEKYB_NAMESPACE::TrajectoryModule::priority [protected] | 
        
Definition at line 39 of file TrajectoryModule.hpp.
Definition at line 29 of file TrajectoryModule.hpp.
TrajModulePosType TELEKYB_NAMESPACE::TrajectoryModule::type [protected] | 
        
Definition at line 34 of file TrajectoryModule.hpp.