Hover.hpp
Go to the documentation of this file.
00001 /*
00002  * HoverBehavior.hpp
00003  *
00004  *  Created on: Nov 3, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef HOVER_HPP_
00009 #define HOVER_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <tk_behavior/Behavior.hpp>
00014 
00015 // Options
00016 #include <telekyb_base/Options.hpp>
00017 
00018 // plugin stuff
00019 //#include <pluginlib/class_list_macros.h>
00020 
00021 using namespace TELEKYB_NAMESPACE;
00022 
00023 namespace telekyb_behavior {
00024 
00025 class Hover : public Behavior {
00026 protected:
00027         // Option
00028         Option<double>* tHoverMaxInitialVelocity;
00029 
00030         // Data
00031         Position3D hoverPosition;
00032         double yawAngle; // explicit, to do only 1 RPY Conversion
00033 
00034         // Init Service
00035         //ros::ServiceServer initService;
00036 
00037 public:
00038         Hover();
00039 
00040         // from BehaviorInterface
00041         virtual void initialize();
00042         virtual void destroy();
00043 
00044         // Called directly after Change Event is registered.
00045         virtual bool willBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00046         // Called after actual Switch. Note: During execution trajectoryStepCreation is used
00047         virtual void didBecomeActive(const TKState& currentState, const Behavior& previousBehavior);
00048         // Called directly after Change Event is registered: During execution trajectoryStepTermination is used
00049         virtual void willBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00050         // Called after actual Switch. Runs in seperate Thread.
00051         virtual void didBecomeInActive(const TKState& currentState, const Behavior& nextBehavior);
00052 
00053         // called everytime a new TKState is available AND it is the NEW Behavior of an active Switch
00054         virtual void trajectoryStepCreation(const TKState& currentState, TKTrajectory& generatedTrajInput);
00055 
00056         // called everytime a new TKState is available. Should return false if invalid (swtich to next behavior, or Hover if undef).
00057         virtual void trajectoryStepActive(const TKState& currentState, TKTrajectory& generatedTrajInput);
00058 
00059         // called everytime a new TKState is available AND it is the OLD Behavior of an active Switch
00060         virtual void trajectoryStepTermination(const TKState& currentState, TKTrajectory& generatedTrajInput);
00061 
00062         // Return true if the active Behavior is (still) valid. Initiate Switch otherwise
00063         virtual bool isValid(const TKState& currentState) const;
00064 
00065 };
00066 
00067 }
00068 
00069 #endif /* HOVERBEHAVIOR_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