Behavior.hpp
Go to the documentation of this file.
00001 /*
00002  * Behavior.hpp
00003  *
00004  *  Created on: Oct 28, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef BEHAVIOR_HPP_
00009 #define BEHAVIOR_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <telekyb_base/Messages.hpp>
00014 
00015 //For OptionContainer
00016 #include <telekyb_base/Options.hpp>
00017 
00018 #include <string>
00019 #include <ros/ros.h>
00020 
00021 // BehaviorType
00022 #include <tk_behavior/BehaviorType.hpp>
00023 
00024 // Interface
00025 #include <tk_behavior/BehaviorInterface.hpp>
00026 
00027 // plugin stuff
00028 #include <pluginlib/class_list_macros.h>
00029 
00030 namespace TELEKYB_NAMESPACE
00031 {
00032 
00033 // forward declaration
00034 class BehaviorController;
00035 
00036 // Interface definition for Behaviors
00037 
00038 // Every Behavior is an OptionContainer
00039 class Behavior : public OptionContainer
00040 {
00041 private:
00042         // cannot be overwritten by Behavior implementations!
00043         BehaviorType type;
00044 
00045 protected:
00046         Behavior(const std::string& name_, const BehaviorType& type_);
00047 
00048         BehaviorController& bController;
00049         // ROS
00050         ros::NodeHandle nodeHandle;
00051 
00052         // name <- set by BehaviorContainer, since it loads by name
00053         std::string name;
00054         //void setName(const std::string& name_);
00055 
00056         // is set to true after Behavior is Parameter-Initalized.
00057         // if Behavior has no Parameters, set this to true within initialize().
00058         bool parameterInitialized;
00059 
00060         // Follow up Behavior -> get's activated if trajectoryStep return false.
00061         Behavior* nextBehavior;
00062 
00063         // Interface for ROS
00064         BehaviorInterface* behaviorInterface;
00065 
00066 public:
00067         // Pure Base Methods
00068         uint64_t getID() const;
00069         std::string getIDString() const;
00070         std::string getName() const;
00071         bool isParameterInitialized() const;
00072         void setParameterInitialized(bool parameterInitialized_);
00073 
00074         // get NodeHandle
00075         const ros::NodeHandle& getNodeHandle() const;
00076 
00077         // returns true if this behavior is the current active one
00078         bool isActive() const;
00079 
00080         // Next Behavior Control
00081         bool setNextBehavior(Behavior* nextBehavior_);
00082         void unsetNextBehavior();
00083         bool hasNextBehavior() const;
00084         Behavior* getNextBehavior() const;
00085 
00086         BehaviorType getType() const;
00087 
00088         // Method with old/current Behavior. This is called by the Controller and will call
00089         bool canTransitionTo(const Behavior& toBehavior) const;
00090 
00091         // called directly after Creation
00092         virtual void initialize() = 0;
00093 
00094         // called right before destruction
00095         virtual void destroy() = 0;
00096 
00097         // called right before Behavior becomes active. Get's the currentState once.
00098         virtual bool willBecomeActive(const TKState& currentState, const Behavior& previousBehavior) = 0;
00099 
00100         // called right after Behavior became active. Get's the currentState once.
00101         virtual void didBecomeActive(const TKState& currentState, const Behavior& previousBehavior) = 0;
00102 
00103         // called right before Behavior becomes inactive
00104         virtual void willBecomeInActive(const TKState& currentState, const Behavior& nextBehavior) = 0;
00105 
00106         // called right after Behavior become inactive
00107         virtual void didBecomeInActive(const TKState& currentState, const Behavior& nextBehavior) = 0;
00108 
00109         // called everytime a new TKState is available AND it is the NEW Behavior of an active Switch
00110         virtual void trajectoryStepCreation(const TKState& currentState, TKTrajectory& generatedTrajInput) = 0;
00111 
00112         // called everytime a new TKState is available. Should return false if invalid (swtich to next behavior, or Hover if undef).
00113         virtual void trajectoryStepActive(const TKState& currentState, TKTrajectory& generatedTrajInput) = 0;
00114 
00115         // called everytime a new TKState is available AND it is the OLD Behavior of an active Switch
00116         virtual void trajectoryStepTermination(const TKState& currentState, TKTrajectory& generatedTrajInput) = 0;
00117 
00118         // Return true if the active Behavior is (still) valid. Initiate Switch otherwise
00119         virtual bool isValid(const TKState& currentState) const = 0;
00120 
00121         // Destructor
00122         virtual ~Behavior();
00123 
00124         // Friend BehaviorContainer to setName
00125         //friend class BehaviorContainer;
00126 
00127         // static Helpers
00128         static Behavior* behaviorFromID(uint64_t behaviorID);
00129         static uint64_t behaviorToID(Behavior* b);
00130         static bool exists(Behavior *behavior);
00131         static bool exists(uint64_t behaviorID);
00132 };
00133 
00134 
00135 } // namepsace
00136 
00137 
00138 #endif /* BEHAVIOR_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