ROSOptionController.hpp
Go to the documentation of this file.
00001 /*
00002  * ROSOptionController.hpp
00003  *
00004  *  Created on: Oct 18, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef ROSOPTIONCONTROLLER_HPP_
00009 #define ROSOPTIONCONTROLLER_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 #include <telekyb_base/ROS/ROSBaseOption.hpp>
00013 #include <telekyb_base/ROS/ROSOptionContainer.hpp>
00014 
00015 #include <telekyb_base/Options/OptionListener.hpp>
00016 
00017 #include <ros/ros.h>
00018 
00019 //stl
00020 #include <set>
00021 
00022 #include <telekyb_srvs/StringOutput.h>
00023 
00024 
00025 namespace TELEKYB_NAMESPACE
00026 {
00027 // forward
00028 class ROSOptionControllerOptions;
00029 
00030 // contains all ROSOptions (in BaseClass Representation)
00031 class ROSOptionController : public OptionListener<double>
00032 {
00033 private:
00034         static std::set<ROSBaseOption*> rosOptions;
00035         static std::set<ROSOptionContainer*> rosOptionContainers;
00036 
00037         static ROSOptionController* instance;
00038 
00039         // Singleton overwrites
00040         ROSOptionController();
00041         virtual ~ROSOptionController();
00042         ROSOptionController(const ROSOptionController &);
00043         ROSOptionController& operator=(const ROSOptionController &);
00044 
00045 
00046 protected:
00047         ROSOptionControllerOptions* options;
00048         // ROS Stuff
00049         ros::NodeHandle optionHandle;
00050         // Timer for Rosupdate
00051         ros::Timer optionUpdateTimer;
00052 
00053         // callback for Timer
00054         void optionUpdateTimerCB(const ros::TimerEvent& event);
00055 
00056         // General Manipulation
00057         void createAllGetSetServices();
00058 
00059         void setAllToParameterServer();
00060         void updateAllFromParameterServer();
00061         void deleteAllFromParameterServer();
00062 
00063         // This function is like the constructor, but called directly AFTER Object creation.
00064         // This is needed, to make calls to Objects that depend on the Singleton and are called
00065         // In this initialization phase.
00066         void initialize();
00067 
00068 
00069         // ROS SERVICES
00070         ros::ServiceServer getOptionNodeHandleSrv;
00071         bool getOptionNodeHandleSrvCB(
00072                         telekyb_srvs::StringOutput::Request& request,
00073                         telekyb_srvs::StringOutput::Response& response);
00074 
00075 public:
00076         const ros::NodeHandle& getOptionNodeHandle() const;
00077         std::string getOptionNodeHandleNamespace() const;
00078 
00079         // double OptionListener
00080         // for tRosOptionUpdatePeriod
00081         virtual void optionDidChange(const Option<double>* option_);
00082 
00083         // static stuff
00084         static bool addROSOption(ROSBaseOption* rosOption);
00085         static bool removeROSOption(ROSBaseOption* rosOption);
00086 
00087         static bool addROSOptionContainer(ROSOptionContainer* rosOptionContainer);
00088         static bool removeROSOptionContainer(ROSOptionContainer* rosOptionContainer);
00089 
00090         // Singleton Stuff
00091         static ROSOptionController& Instance();
00092         static const ROSOptionController* InstancePtr();
00093         static void ShutDownInstance();
00094         static bool hasInstance();
00095 };
00096 
00097 }
00098 
00099 #endif /* ROSOPTIONCONTROLLER_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_base
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:12:34