00001 /* 00002 * BehaviorController.hpp 00003 * 00004 * Created on: Nov 15, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef INTERFACE_BEHAVIORCONTROLLER_HPP_ 00009 #define INTERFACE_BEHAVIORCONTROLLER_HPP_ 00010 00011 #include <telekyb_defines/telekyb_defines.hpp> 00012 00013 #include <ros/ros.h> 00014 00015 #include <telekyb_interface/Behavior.hpp> 00016 #include <telekyb_interface/OptionController.hpp> 00017 00018 #include <telekyb_msgs/Behavior.h> 00019 00020 namespace TELEKYB_INTERFACE_NAMESPACE { 00021 00022 // ActiveBehaviorListener 00023 00024 class ActiveBehaviorListener { 00025 public: 00026 virtual void activeBehaviorChanged(Behavior newActiveBehavior) = 0; 00027 }; 00028 00029 class BehaviorController { 00030 protected: 00031 ros::NodeHandle behaviorControllerNodeHandle; 00032 // OptionController 00033 OptionController* optionController; 00034 00035 // active Behavior 00036 Behavior activeBehavior; 00037 00038 ros::Subscriber activeBehaviorSub; 00039 00040 // get Active 00041 Behavior getActiveBehavior(); 00042 00043 // Listener // only one at ATM 00044 ActiveBehaviorListener* listener; 00045 00046 public: 00047 BehaviorController(const std::string& behaviorHandleNamespace, OptionController* optionController_); 00048 virtual ~BehaviorController(); 00049 00050 // return Nodehandle 00051 const ros::NodeHandle& getNodeHandle() const; 00052 00053 // return OptionController 00054 OptionController* getOptionController() const; 00055 00056 // System Behaviors are only loaded Once and can be referenced by Name. 00057 Behavior getSystemBehavior(const std::string& behaviorName); 00058 // Get Available Behaviors. 00059 bool getAvailableBehaviors(std::vector<std::string>& behaviorNames); 00060 Behavior loadBehavior(const std::string& behaviorName); 00061 bool unloadBehavior(Behavior& behavior); 00062 00063 // Switch 00064 bool switchBehavior(const Behavior& behavior); 00065 00066 // Current Behavior Pointer -> updates live 00067 Behavior* getActiveBehaviorPointer(); 00068 const Behavior& getActiveBehaviorReference() const; 00069 00070 // active Behavior Callback 00071 void activeBehaviorCallback(const telekyb_msgs::Behavior::ConstPtr& msg); 00072 00073 // setActiveBehaviorListener; 00074 void setActiveBehaviorListener(ActiveBehaviorListener* listener_); 00075 }; 00076 00077 } 00078 00079 #endif /* BEHAVIORCONTROLLER_HPP_ */