00001 /* 00002 * TrajectoryController.hpp 00003 * 00004 * Created on: Nov 8, 2011 00005 * Author: mriedel 00006 */ 00007 00008 #ifndef TRAJECTORYCONTROLLER_HPP_ 00009 #define TRAJECTORYCONTROLLER_HPP_ 00010 00011 #include <telekyb_defines/telekyb_defines.hpp> 00012 00013 #include <tk_trajctrl/TrajectoryControllerOptions.hpp> 00014 00015 // TrajInput 00016 #include <telekyb_base/Messages.hpp> 00017 00018 // Telekyb Msgs 00019 #include <telekyb_msgs/TKState.h> 00020 00021 // Ros 00022 #include <ros/ros.h> 00023 00024 // Boost 00025 #include <boost/thread/mutex.hpp> 00026 00027 // Class Loading 00028 #include <pluginlib/class_loader.h> 00029 00030 // Interface Definition 00031 #include <tk_trajctrl/TrajectoryTracker.hpp> 00032 00033 namespace TELEKYB_NAMESPACE { 00034 00035 /* 00036 * OptionListener<bool> -> if MassEstimation is completely disabled! 00037 */ 00038 00039 class TrajectoryController { 00040 private: 00041 // Singleton Stuff 00042 static TrajectoryController* instance; 00043 00044 TrajectoryController(); 00045 virtual ~TrajectoryController(); 00046 00047 TrajectoryController(const TrajectoryController &); 00048 TrajectoryController& operator=(const TrajectoryController &); 00049 00050 protected: 00051 TrajectoryControllerOptions options; 00052 00053 // ClassLoader 00054 pluginlib::ClassLoader<TrajectoryTracker> ttLoader; 00055 00056 // active State 00057 TrajectoryTracker* activeTrajectoryTracker; 00058 00059 // Nodehandle 00060 ros::NodeHandle nodeHandle; 00061 // Subscribe to TKState 00062 ros::Subscriber tTcStateSub; 00063 00064 // initialize. This does further setup AFTER the object has been created. 00065 // This is needed, since Objects that reference the Behavior Controller can only be created after it returns from the constuctor 00066 // (Singleton Issue). 00067 //** This is like a Constructor. It's called by the Singleton creator DIRECTLY AFTER the actual constructor. **/ 00068 void initialize(); 00069 00070 00071 00072 public: 00073 void trajInputStep(const TKTrajectory& nextInput); 00074 //void toggleMassEstimation(bool toggleME); 00075 00076 void tkStateCB(const telekyb_msgs::TKState::ConstPtr& msg); 00077 00078 00079 // Singleton Stuff 00080 static TrajectoryController& Instance(); 00081 static TrajectoryController* InstancePtr(); 00082 static bool HasInstance(); 00083 static void ShutDownInstance(); 00084 }; 00085 00086 } 00087 00088 #endif /* TRAJECTORYCONTOLLER_HPP_ */