ROSModule.cpp
Go to the documentation of this file.
00001 /*
00002  * ROSModule.cpp
00003  *
00004  *  Created on: Oct 18, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #include <telekyb_base/ROS/ROSModule.hpp>
00009 
00010 #include <telekyb_base/Options/OptionContainer.hpp>
00011 
00012 #include <boost/lexical_cast.hpp>
00013 
00014 #include <telekyb_base/Options/CommonOptions.hpp>
00015 
00016 namespace TELEKYB_NAMESPACE
00017 {
00018 
00019 class ROSModuleOptions : public OptionContainer
00020 {
00021 public:
00022         BoundsOption<int>* tRosNrSpinnerThreads;
00023         Option<std::string>* tRosMainHandleSuffix;
00024 
00025         ROSModuleOptions()
00026                 : OptionContainer("ROSModule")
00027         {
00028                 tRosNrSpinnerThreads = addBoundsOption<int>("tRosNrSpinnerThreads",
00029                                 "# of Threads create by the ros::AsyncSpinner. 0 uses # of cores. -1 disables", 2, -1, 8, false, true);
00030                 tRosMainHandleSuffix = addOption<std::string>("tRosMainHandleSuffix",
00031                                 "Specifiy an alternative NodeHandle Suffix", ros::this_node::getName(), false, true);
00032         }
00033 };
00034 
00035 ROSModule::ROSModule()
00036 {
00037         options = new ROSModuleOptions();
00038 //      if (!options->tRosMainHandleSuffix->isOnInitialValue()) {
00039 //              // Use User Nodename
00040 //              nodeHandleSuffix_ = options->tRosMainHandleSuffix->getValue();
00041 //      }
00042 
00043         baseNodeHandle = ros::NodeHandle(std::string(TELEKYB_BASENAME));
00044         mainNodeHandle = ros::NodeHandle(std::string(TELEKYB_BASENAME) + "/" + options->tRosMainHandleSuffix->getValue() );
00045         nodeNameNodeHandle = ros::NodeHandle(std::string(TELEKYB_BASENAME) + "/" + CommonOptions::Instance().getNodeName() );
00046 
00047         if ( options->tRosNrSpinnerThreads->getValue() < 0) {
00048                 spinner = NULL;
00049         } else {
00050                 spinner = new ros::AsyncSpinner( options->tRosNrSpinnerThreads->getValue() );
00051                 spinner->start();
00052         }
00053 }
00054 
00055 ROSModule::~ROSModule()
00056 {
00057         if (spinner) {
00058                 spinner->stop();
00059                 delete spinner;
00060         }
00061         delete options;
00062 }
00063 
00064 const ros::NodeHandle& ROSModule::getMainNodeHandle() const
00065 {
00066         return mainNodeHandle;
00067 }
00068 const ros::NodeHandle& ROSModule::getBaseNodeHandle() const
00069 {
00070         return baseNodeHandle;
00071 }
00072 const ros::NodeHandle& ROSModule::getNodeNameNodeHandle() const
00073 {
00074         return nodeNameNodeHandle;
00075 }
00076 
00077 
00078 std::string ROSModule::getNodeName() const
00079 {
00080         return ros::this_node::getName();
00081 }
00082 
00083 
00084 // Singleton Stuff
00085 ROSModule* ROSModule::instance = NULL;
00086 
00087 ROSModule& ROSModule::Instance() {
00088         if (!instance) {
00089                 instance = new ROSModule();
00090         }
00091         return *instance;
00092 }
00093 
00094 const ROSModule* ROSModule::InstancePtr() {
00095         if (!instance) {
00096                 instance = new ROSModule();
00097         }
00098 
00099         return instance;
00100 }
00101 
00102 bool ROSModule::HasInstance()
00103 {
00104         return (instance != NULL);
00105 }
00106 
00107 void ROSModule::ShutDownInstance() {
00108         if (instance) {
00109                 delete instance;
00110         }
00111 
00112         instance = NULL;
00113 }
00114 
00115 }
 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