#include <TrajectoryInput.hpp>

Public Member Functions | |
| virtual void | destroy () |
| virtual void | didBecomeActive (const TKState ¤tState, const Behavior &previousBehavior) |
| virtual void | didBecomeInActive (const TKState ¤tState, const Behavior &nextBehavior) |
| virtual void | initialize () |
| virtual bool | isValid (const TKState ¤tState) const |
| TrajectoryInput () | |
| virtual void | trajectoryStepActive (const TKState ¤tState, TKTrajectory &generatedTrajInput) |
| virtual void | trajectoryStepCreation (const TKState ¤tState, TKTrajectory &generatedTrajInput) |
| virtual void | trajectoryStepTermination (const TKState ¤tState, TKTrajectory &generatedTrajInput) |
| virtual bool | willBecomeActive (const TKState ¤tState, const Behavior &previousBehavior) |
| virtual void | willBecomeInActive (const TKState ¤tState, const Behavior &nextBehavior) |
| virtual | ~TrajectoryInput () |
Protected Member Functions | |
| void | trajectoryCB (const telekyb_msgs::TKTrajectory::ConstPtr &msg) |
Protected Attributes | |
| TKTrajectory | lastMsg |
| ros::NodeHandle | nodeHandle |
| Timer | timeoutTimer |
| ros::Subscriber | trajectorySub |
| Option< double > * | tTrajectoryTimeout |
| Option< std::string > * | tTrajectoryTopicName |
Definition at line 27 of file TrajectoryInput.hpp.
Definition at line 18 of file TrajectoryInput.cpp.
| telekyb_behavior::TrajectoryInput::~TrajectoryInput | ( | ) | [virtual] |
Definition at line 25 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::destroy | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 53 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::didBecomeActive | ( | const TKState & | currentState, |
| const Behavior & | previousBehavior | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 71 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::didBecomeInActive | ( | const TKState & | currentState, |
| const Behavior & | nextBehavior | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 81 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::initialize | ( | ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 37 of file TrajectoryInput.cpp.
| bool telekyb_behavior::TrajectoryInput::isValid | ( | const TKState & | currentState | ) | const [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 111 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::trajectoryCB | ( | const telekyb_msgs::TKTrajectory::ConstPtr & | msg | ) | [protected] |
Definition at line 30 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::trajectoryStepActive | ( | const TKState & | currentState, |
| TKTrajectory & | generatedTrajInput | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 94 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::trajectoryStepCreation | ( | const TKState & | currentState, |
| TKTrajectory & | generatedTrajInput | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 87 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::trajectoryStepTermination | ( | const TKState & | currentState, |
| TKTrajectory & | generatedTrajInput | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 104 of file TrajectoryInput.cpp.
| bool telekyb_behavior::TrajectoryInput::willBecomeActive | ( | const TKState & | currentState, |
| const Behavior & | previousBehavior | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 58 of file TrajectoryInput.cpp.
| void telekyb_behavior::TrajectoryInput::willBecomeInActive | ( | const TKState & | currentState, |
| const Behavior & | nextBehavior | ||
| ) | [virtual] |
Implements TELEKYB_NAMESPACE::Behavior.
Definition at line 76 of file TrajectoryInput.cpp.
Definition at line 40 of file TrajectoryInput.hpp.
Reimplemented from TELEKYB_NAMESPACE::Behavior.
Definition at line 33 of file TrajectoryInput.hpp.
Timer telekyb_behavior::TrajectoryInput::timeoutTimer [protected] |
Definition at line 37 of file TrajectoryInput.hpp.
Definition at line 34 of file TrajectoryInput.hpp.
Option<double>* telekyb_behavior::TrajectoryInput::tTrajectoryTimeout [protected] |
Definition at line 30 of file TrajectoryInput.hpp.
Option<std::string>* telekyb_behavior::TrajectoryInput::tTrajectoryTopicName [protected] |
Definition at line 29 of file TrajectoryInput.hpp.