TeleKybCoreInterface.hpp
Go to the documentation of this file.
00001 /*
00002  * TeleKybCoreInterface.hpp
00003  *
00004  *  Created on: Nov 14, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef TELEKYBCOREINTERFACE_HPP_
00009 #define TELEKYBCOREINTERFACE_HPP_
00010 
00011 #include <telekyb_defines/telekyb_defines.hpp>
00012 
00013 #include <ros/ros.h>
00014 
00015 #include <telekyb_srvs/StringOutput.h>
00016 
00017 namespace TELEKYB_NAMESPACE {
00018 
00019 class TeleKybCoreInterface {
00020 protected:
00021         int robotID;
00022 
00023         ros::NodeHandle robotIDNodeHandle;
00024         ros::NodeHandle mainNodeHandle;
00025 
00026         // This is announces at /TeleKyb/#RobotID/getMainNodeHandle
00027         ros::ServiceServer getMainNodeHandle;
00028 
00029 //      ros::ServiceServer getOptionNodeHandle;
00030         ros::ServiceServer getStateNodeHandle;
00031         ros::ServiceServer getBehaviorNodeHandle;
00032 
00033         bool getMainNodeHandleCB(
00034                         telekyb_srvs::StringOutput::Request& request,
00035                         telekyb_srvs::StringOutput::Response& response);
00036 //      bool getOptionNodeHandleCB(
00037 //                      telekyb_srvs::StringOutput::Request& request,
00038 //                      telekyb_srvs::StringOutput::Response& response);
00039         bool getStateNodeHandleCB(
00040                         telekyb_srvs::StringOutput::Request& request,
00041                         telekyb_srvs::StringOutput::Response& response);
00042         bool getBehaviorNodeHandleCB(
00043                         telekyb_srvs::StringOutput::Request& request,
00044                         telekyb_srvs::StringOutput::Response& response);
00045 
00046 public:
00047         TeleKybCoreInterface(int robotID_);
00048         virtual ~TeleKybCoreInterface();
00049 };
00050 
00051 } /* namespace telekyb */
00052 #endif /* TELEKYBCOREINTERFACE_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_core
Author(s): Dr. Antonio Franchi and Martin Riedel
autogenerated on Mon Nov 11 2013 11:13:47