#include <StandardTrajectoryTracker.hpp>
Public Member Functions | |
| void | destroy () | 
| std::string | getName () const | 
| void | initialize () | 
| StandardTrajectoryTracker () | |
| void | stateCB (const TKState &state) | 
| void | trajectoryCB (const TKTrajectory &trajectory) | 
| virtual | ~StandardTrajectoryTracker () | 
Protected Attributes | |
| ros::NodeHandle | commandNodeHandle | 
| TKTrajectory | currentInput | 
| boost::mutex | currentInputMutex | 
| double | currentMass | 
| MassEstimator * | massEstimator | 
| pluginlib::ClassLoader < MassEstimator >  | meLoader | 
| ros::NodeHandle | nodeHandle | 
| StandardTrajectoryTrackerOptions | options | 
| PositionControl | positionControl | 
| Option< bool > * | tDoMassEstimation | 
| ros::Publisher | tTcCommandsPub | 
| YawControl | yawControl | 
Definition at line 52 of file StandardTrajectoryTracker.hpp.
Definition at line 38 of file StandardTrajectoryTracker.cpp.
Definition at line 48 of file StandardTrajectoryTracker.cpp.
| void TELEKYB_NAMESPACE::StandardTrajectoryTracker::destroy | ( | ) |  [virtual] | 
        
Implements TELEKYB_NAMESPACE::TrajectoryTracker.
Definition at line 95 of file StandardTrajectoryTracker.cpp.
| std::string TELEKYB_NAMESPACE::StandardTrajectoryTracker::getName | ( | ) |  const [virtual] | 
        
Implements TELEKYB_NAMESPACE::TrajectoryTracker.
Definition at line 100 of file StandardTrajectoryTracker.cpp.
| void TELEKYB_NAMESPACE::StandardTrajectoryTracker::initialize | ( | ) |  [virtual] | 
        
Implements TELEKYB_NAMESPACE::TrajectoryTracker.
Definition at line 56 of file StandardTrajectoryTracker.cpp.
| void TELEKYB_NAMESPACE::StandardTrajectoryTracker::stateCB | ( | const TKState & | state | ) |  [virtual] | 
        
Implements TELEKYB_NAMESPACE::TrajectoryTracker.
Definition at line 112 of file StandardTrajectoryTracker.cpp.
| void TELEKYB_NAMESPACE::StandardTrajectoryTracker::trajectoryCB | ( | const TKTrajectory & | trajectory | ) |  [virtual] | 
        
Implements TELEKYB_NAMESPACE::TrajectoryTracker.
Definition at line 106 of file StandardTrajectoryTracker.cpp.
Definition at line 76 of file StandardTrajectoryTracker.hpp.
Definition at line 72 of file StandardTrajectoryTracker.hpp.
boost::mutex TELEKYB_NAMESPACE::StandardTrajectoryTracker::currentInputMutex [protected] | 
        
Definition at line 71 of file StandardTrajectoryTracker.hpp.
double TELEKYB_NAMESPACE::StandardTrajectoryTracker::currentMass [protected] | 
        
Definition at line 69 of file StandardTrajectoryTracker.hpp.
Definition at line 61 of file StandardTrajectoryTracker.hpp.
pluginlib::ClassLoader<MassEstimator> TELEKYB_NAMESPACE::StandardTrajectoryTracker::meLoader [protected] | 
        
Definition at line 58 of file StandardTrajectoryTracker.hpp.
Definition at line 75 of file StandardTrajectoryTracker.hpp.
Definition at line 63 of file StandardTrajectoryTracker.hpp.
Definition at line 64 of file StandardTrajectoryTracker.hpp.
Option<bool>* TELEKYB_NAMESPACE::StandardTrajectoryTracker::tDoMassEstimation [protected] | 
        
Definition at line 55 of file StandardTrajectoryTracker.hpp.
Definition at line 79 of file StandardTrajectoryTracker.hpp.
Definition at line 65 of file StandardTrajectoryTracker.hpp.