Option.hpp
Go to the documentation of this file.
00001 /*
00002  * Option.hpp
00003  *
00004  *  Created on: Nov 15, 2011
00005  *      Author: mriedel
00006  */
00007 
00008 #ifndef INTERFACE_OPTION_HPP_
00009 #define INTERFACE_OPTION_HPP_
00010 
00011 #include <string>
00012 
00013 #include <ros/ros.h>
00014 
00015 #include <telekyb_defines/telekyb_defines.hpp>
00016 
00017 #include <telekyb_base/Tools/XmlRpcConversion.hpp>
00018 #include <telekyb_base/Tools/YamlHelper.hpp>
00019 
00020 #include <telekyb_srvs/StringInput.h>
00021 #include <telekyb_srvs/StringOutput.h>
00022 
00023 
00024 namespace TELEKYB_INTERFACE_NAMESPACE {
00025 
00026 class Option {
00027 private:
00028         // only created by OptionController or Optioncontainer
00029         Option(const ros::NodeHandle& optionNSNodehandle_, const std::string& optionName_);
00030 
00031 protected:
00032         // reference to NodeHandle
00033         ros::NodeHandle optionNSNodehandle;
00034         std::string optionName;
00035 
00036 
00037 
00038 public:
00039 //      Option();
00040         virtual ~Option();
00041 
00042 
00043         // exists?
00044         bool exists();
00045 
00046         // setter and getter
00047         template <class _T>
00048         bool get(_T& optionValue)
00049         {
00050                 ros::NodeHandle optionServiceNodehandle(optionNSNodehandle, optionName);
00051                 ros::ServiceClient client = optionServiceNodehandle.serviceClient<telekyb_srvs::StringOutput>(OPTION_GETSERVICE_NAME);
00052 
00053                 telekyb_srvs::StringOutput soService;
00054                 if (!client.call(soService)) {
00055                         ROS_ERROR_STREAM("Unable to get Option. Failed to call: " << client.getService());
00056                         return false;
00057                 }
00058 
00059                 // Error print should be in here
00060                 return telekyb::YamlHelper::parseStringToValue(soService.response.output, optionValue);
00061         }
00062 
00063         template <class _T>
00064         bool set(const _T& optionValue)
00065         {
00066                 ros::NodeHandle optionServiceNodehandle(optionNSNodehandle, optionName);
00067                 ros::ServiceClient client = optionServiceNodehandle.serviceClient<telekyb_srvs::StringInput>(OPTION_SETSERVICE_NAME);
00068                 telekyb_srvs::StringInput siService;
00069                 if (! telekyb::YamlHelper::parseValueToString(optionValue, siService.request.input) ) {
00070                         return false;
00071                 }
00072                 // everything ok.
00073                 if (!client.call(siService)) {
00074                         ROS_ERROR_STREAM("Unable to set Option. Failed to call: " << client.getService());
00075                         return false;
00076                 }
00077 
00078                 return true;
00079         }
00080 
00081         // async uses Paramter server
00082         template <class _T>
00083         bool getAsync(_T& optionValue)
00084         {
00085                 XmlRpc::XmlRpcValue value;
00086                 optionNSNodehandle.getParam(optionName, value);
00087 
00088                 // Conversion
00089                 try {
00090                         value >> optionValue;
00091                 } catch (XmlRpc::XmlRpcException &e) {
00092                         // value On Ros is invalid! Revert to Optionvalue.
00093                         ROS_ERROR_STREAM("Could not convert Option " << optionName << " FROM XmlRpcValue! " << e.getMessage());
00094                         return false;
00095                 }
00096                 return true;
00097         }
00098 
00099         template <class _T>
00100         bool setAsync(const _T& optionValue)
00101         {
00102                 XmlRpc::XmlRpcValue value;
00103                 try {
00104                         optionValue >> value;
00105                         optionNSNodehandle.setParam(optionName, value);
00106                 } catch (XmlRpc::XmlRpcException &e) {
00107                         ROS_ERROR_STREAM("Could not convert Option " << optionName << " to XmlRpcValue! " << e.getMessage());
00108                         return false;
00109                 }
00110                 return true;
00111         }
00112 
00113         // allowed to create Options
00114         friend class OptionController;
00115         friend class OptionContainer;
00116 };
00117 
00118 } /* namespace telekyb_interface */
00119 #endif /* OPTION_HPP_ */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends Defines


telekyb_interface
Author(s): Martin Riedel
autogenerated on Mon Nov 11 2013 11:12:47