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