TrajectoryInput.hpp
Go to the documentation of this file.
00001 /*
00002  * TrajectoryInput.hpp
00003  *
00004  *  Created on: Mar 2, 2012
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef TRAJECTORYINPUT_HPP_
00009 #define TRAJECTORYINPUT_HPP_
00010 
00011 
00012 #include <telekyb_defines/telekyb_defines.hpp>
00013 #include <tk_behavior/Behavior.hpp>
00014 
00015 // plugin stuff
00016 #include <pluginlib/class_list_macros.h>
00017 
00018 
00019 
00020 // Timer
00021 #include <telekyb_base/Time.hpp>
00022 
00023 using namespace TELEKYB_NAMESPACE;
00024 
00025 namespace telekyb_behavior {
00026 
00027 class TrajectoryInput : public Behavior {
00028 protected:
00029         Option<std::string>* tTrajectoryTopicName;
00030         Option<double>* tTrajectoryTimeout;
00031 
00032         // ROS
00033         ros::NodeHandle nodeHandle;
00034         ros::Subscriber trajectorySub;
00035 
00036         // Timer
00037         Timer timeoutTimer;
00038 
00039         // Last Trajectory Msgs
00040         TKTrajectory lastMsg;
00041 //      telekyb_msgs::TKTrajectory lastMsg;
00042 
00043         // CB
00044         void trajectoryCB(const telekyb_msgs::TKTrajectory::ConstPtr& msg);
00045 
00046 public:
00047         TrajectoryInput();
00048         virtual ~TrajectoryInput();
00049 
00050         virtual void initialize();
00051         virtual void destroy();
00052 
00053         // Called directly after Change Event is registered.
00054         virtual bool willBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00055         // Called after actual Switch. Note: During execution trajectoryStepCreation is used
00056         virtual void didBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00057         // Called directly after Change Event is registered: During execution trajectoryStepTermination is used
00058         virtual void willBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00059         // Called after actual Switch. Runs in seperate Thread.
00060         virtual void didBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00061 
00062         // called everytime a new TKState is available AND it is the NEW Behavior of an active Switch
00063         virtual void trajectoryStepCreation(const TKState& currentState, TKTrajectory& generatedTrajInput);
00064 
00065         // called everytime a new TKState is available. Should return false if invalid (swtich to next behavior, or Hover if undef).
00066         virtual void trajectoryStepActive(const TKState& currentState, TKTrajectory& generatedTrajInput);
00067 
00068         // called everytime a new TKState is available AND it is the OLD Behavior of an active Switch
00069         virtual void trajectoryStepTermination(const TKState& currentState, TKTrajectory& generatedTrajInput);
00070 
00071         // Return true if the active Behavior is (still) valid. Initiate Switch otherwise
00072         virtual bool isValid(const TKState& currentState) const;
00073 
00074 };
00075 
00076 }
00077 
00078 #endif /* TRAJECTORYINPUT_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


tk_be_common
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:14:29