TrajectoryProcessorController.hpp
Go to the documentation of this file.
00001 /*
00002  * TrajectoryProcessorController.hpp
00003  *
00004  *  Created on: Dec 13, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef TRAJECTORYPROCESSORCONTROLLER_HPP_
00009 #define TRAJECTORYPROCESSORCONTROLLER_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <telekyb_defines/ClassInterfaces.hpp>
00013 
00014 #include <tk_trajprocessor/TrajectoryProcessorControllerOptions.hpp>
00015 #include <tk_trajprocessor/TrajectoryModuleContainer.hpp>
00016 
00017 #include <tk_state/StateEstimatorController.hpp>
00018 
00019 #include <boost/thread/mutex.hpp>
00020 
00021 namespace TELEKYB_NAMESPACE {
00022 
00023 class TrajectoryController;
00024 
00025 class TrajectoryProcessorController {
00026 private:
00027         // Singleton Stuff
00028         static TrajectoryProcessorController* instance;
00029 
00030         TrajectoryProcessorController();
00031         virtual ~TrajectoryProcessorController();
00032 
00033         TrajectoryProcessorController(const TrajectoryProcessorController &);
00034         TrajectoryProcessorController& operator=(const TrajectoryProcessorController &);
00035 
00036 
00037 protected:
00038         //** This is like a Constructor. It's called by the Singleton creator DIRECTLY AFTER the actual constructor. **/
00039         void initialize();
00040 
00041         // Options
00042         TrajectoryProcessorControllerOptions options;
00043 
00044         // BehaviorNodeHandle
00045         ros::NodeHandle trajProcessorNodeHandle;
00046 
00047         // State Subscription
00048         ros::Subscriber tStateSub;
00049 
00050         // StateEstimatorController Instance!
00051         StateEstimatorController& seController;
00052 
00053         // where to send the TKTrajInput
00054         TrajectoryController& trajController;
00055 
00056         // Callback
00057         TKState lastState;
00058         boost::mutex lastStateMutex;
00059         void tkStateCB(const telekyb_msgs::TKState::ConstPtr& tkStateMsg);
00060 
00061 
00062         // Modules
00063         TrajectoryModuleContainer trajModuleContainer;
00064 
00065         // Active?
00066         bool active;
00067         BehaviorSwitcher* switcher;
00068 
00069 public:
00070         void setActive(BehaviorSwitcher* switcher_);
00071         void setInActive();
00072         bool isActive() const;
00073 
00074         BehaviorSwitcher* getBehaviorSwitcher() const;
00075 
00076         // TKTrajInputReceiver Delegate
00077         void trajInputStep(const TKTrajectory& input);
00078 
00079 
00080         // Singleton Stuff
00081         static TrajectoryProcessorController& Instance();
00082         static const TrajectoryProcessorController* InstancePtr();
00083         static bool HasInstance();
00084         static void ShutDownInstance();
00085 };
00086 
00087 } /* namespace telekyb */
00088 #endif /* TRAJECTORYPROCESSORCONTROLLER_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


tk_trajprocessor
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:29