Land.hpp
Go to the documentation of this file.
00001 /*
00002  * Land.hpp
00003  *
00004  *  Created on: Nov 10, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef LAND_HPP_
00009 #define LAND_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <tk_behavior/Behavior.hpp>
00013 
00014 // plugin stuff
00015 //#include <pluginlib/class_list_macros.h>
00016 
00017 using namespace TELEKYB_NAMESPACE;
00018 
00019 namespace telekyb_behavior {
00020 
00021 class Land : public Behavior {
00022 protected:
00023         Option<Position3D>* tLandDestination;
00024         Option<double>* tLandVelocity;
00025         Option<double>* tLandDestinationHeight;
00026         Option<bool>* tLandVertically;
00027 
00028         Position3D actualLandDestination;
00029         double yawAngle;
00030 
00031 
00032 public:
00033         Land();
00034 
00035         virtual void initialize();
00036         virtual void destroy();
00037 
00038         // Called directly after Change Event is registered.
00039         virtual bool willBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00040         // Called after actual Switch. Note: During execution trajectoryStepCreation is used
00041         virtual void didBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00042         // Called directly after Change Event is registered: During execution trajectoryStepTermination is used
00043         virtual void willBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00044         // Called after actual Switch. Runs in seperate Thread.
00045         virtual void didBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00046 
00047         // called everytime a new TKState is available AND it is the NEW Behavior of an active Switch
00048         virtual void trajectoryStepCreation(const TKState& currentState, TKTrajectory& generatedTrajInput);
00049 
00050         // called everytime a new TKState is available. Should return false if invalid (swtich to next behavior, or Hover if undef).
00051         virtual void trajectoryStepActive(const TKState& currentState, TKTrajectory& generatedTrajInput);
00052 
00053         // called everytime a new TKState is available AND it is the OLD Behavior of an active Switch
00054         virtual void trajectoryStepTermination(const TKState& currentState, TKTrajectory& generatedTrajInput);
00055 
00056         // Return true if the active Behavior is (still) valid. Initiate Switch otherwise
00057         virtual bool isValid(const TKState& currentState) const;
00058 };
00059 
00060 }
00061 
00062 #endif /* LAND_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


tk_behavior
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:36