00001 /* 00002 * BehaviorController.hpp 00003 * 00004 * Created on: Nov 3, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef BEHAVIORCONTROLLER_HPP_ 00009 #define BEHAVIORCONTROLLER_HPP_ 00010 00011 #include <telekyb_defines/telekyb_defines.hpp> 00012 00013 // BehaviorSwitcher Interface 00014 #include <telekyb_defines/ClassInterfaces.hpp> 00015 00016 #include <telekyb_base/Messages.hpp> 00017 00018 #include <tk_behavior/BehaviorControllerInterface.hpp> 00019 #include <tk_behavior/ActiveBehaviorContainer.hpp> 00020 00021 // BehaviorContainers. Systemcontains preloaded Behaviors 00022 #include <tk_behavior/SystemBehaviorContainer.hpp> 00023 00024 #include <tk_behavior/Behavior.hpp> 00025 00026 #include <ros/ros.h> 00027 00028 namespace TELEKYB_NAMESPACE { 00029 00030 //forward declaration 00031 class TrajectoryProcessorController; 00032 00033 class BehaviorController : public BehaviorSwitcher { 00034 private: 00035 // Singleton Stuff 00036 static BehaviorController* instance; 00037 00038 BehaviorController(); 00039 virtual ~BehaviorController(); 00040 00041 BehaviorController(const BehaviorController &); 00042 BehaviorController& operator=(const BehaviorController &); 00043 00044 protected: 00045 // BehaviorNodeHandle 00046 ros::NodeHandle behaviorNodeHandle; 00047 00048 // State Subscription 00049 ros::Subscriber tStateSub; 00050 00051 // BehaviorController Parts 00052 //BehaviorControllerOptions options; 00053 SystemBehaviorContainer* systemBehaviorContainer; 00054 BehaviorControllerInterface* bcInterface; 00055 00056 00057 // active Behavior 00058 ActiveBehaviorContainer* activeBehavior; 00059 // Behavior* activeBehavior; 00060 // BehaviorSwitch behaviorSwitcher; // responsible for the Switch. 00061 00062 // Last TKTrajInput 00063 TKTrajectory lastInput; 00064 00065 // where to send the TKTrajInput 00066 TrajectoryProcessorController& trajProcCtrl; 00067 00068 00069 // initialize. This does further setup AFTER the object has been created. 00070 // This is needed, since Objects that reference the Behavior Controller can only be created after it returns from the constuctor 00071 // (Singleton Issue). 00072 //** This is like a Constructor. It's called by the Singleton creator DIRECTLY AFTER the actual constructor. **/ 00073 void initialize(); 00074 00075 // Callback 00076 void tkStateCB(const telekyb_msgs::TKState::ConstPtr& tkStateMsg); 00077 00078 public: 00079 00080 const ros::NodeHandle& getBehaviorNodeHandle() const; 00081 Behavior* getActiveBehavior() const; 00082 00083 // Switch Behavior 00084 bool switchToBehavior(Behavior* newBehavior); 00085 00086 const SystemBehaviorContainer& getSystemBehaviorContainer() const; 00087 00088 bool switchToNormalBrake(); 00089 bool switchToEmergencyLand(); 00090 00091 void activeBehaviorChanged(); 00092 00093 // Singleton Stuff 00094 static BehaviorController& Instance(); 00095 static const BehaviorController* InstancePtr(); 00096 static bool HasInstance(); 00097 static void ShutDownInstance(); 00098 }; 00099 00100 } 00101 00102 #endif /* BEHAVIORCONTROLLER_HPP_ */