ROSModule.hpp
Go to the documentation of this file.
00001 /*
00002  * ROSModule.h
00003  *
00004  *  Created on: Oct 18, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef ROSMODULE_HPP_
00009 #define ROSMODULE_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 //ros
00014 #include <ros/node_handle.h>
00015 #include <ros/spinner.h>
00016 
00017 namespace TELEKYB_NAMESPACE {
00018 
00019 // forward
00020 class ROSModuleOptions;
00021 
00022 // Central Unit to Extract ROS Stuff from the node
00023 class ROSModule {
00024 private:
00025         static ROSModule* instance;
00026         // Singleton overwrites
00027         ROSModule();
00028 
00029         virtual ~ROSModule();
00030         ROSModule(const ROSModule &);
00031         ROSModule& operator=(const ROSModule &);
00032 
00033 protected:
00034         ROSModuleOptions* options;
00035         ros::NodeHandle baseNodeHandle;
00036         ros::NodeHandle mainNodeHandle;
00037         ros::NodeHandle nodeNameNodeHandle;
00038         ros::AsyncSpinner* spinner;
00039 
00040 
00041 public:
00042 
00043         const ros::NodeHandle& getMainNodeHandle() const;
00044         const ros::NodeHandle& getBaseNodeHandle() const;
00045 
00046         // return the non-anonymous Nodename
00047         const ros::NodeHandle& getNodeNameNodeHandle() const;
00048 
00049         std::string getNodeName() const;
00050 
00051         // Singleton Stuff
00052         static ROSModule& Instance();
00053         static const ROSModule* InstancePtr();
00054         static ROSModule& InstanceWithNodeHandleSuffix(const std::string& nodeHandleSuffix_);
00055         static ROSModule& InstanceWithRobotID(int robotID_);
00056         static bool HasInstance();
00057         static void ShutDownInstance();
00058 
00059 };
00060 
00061 }
00062 
00063 #endif /* ROSMODULE_H_ */
 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