Classes | Macros | Functions
rtt_rosparam_service.cpp File Reference
#include <rtt/RTT.hpp>
#include <rtt/Property.hpp>
#include <rtt/plugin/ServicePlugin.hpp>
#include <rtt/types/PropertyDecomposition.hpp>
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/is_convertible.hpp>
#include <XmlRpcException.h>
#include <Eigen/Dense>
#include <ros/ros.h>
#include <rtt_rosparam/rosparam.h>
Include dependency graph for rtt_rosparam_service.cpp:

Go to the source code of this file.

Classes

class  ROSParamService
 
struct  XmlParamToValue< XMLRPCType, PropertyType, enabled >
 
struct  XmlParamToValue< XMLRPCType, PropertyType, typename boost::enable_if< boost::is_convertible< XMLRPCType, PropertyType > >::type >
 

Macros

#define ADD_ROSPARAM_OPERATION(return_type_str, return_type, func)
 
#define RETURN_RTT_PROPERTY_CONTAINER_TO_XML_PARAM(type, elem_type, prop)   if(castable< type >(prop)) { return rttPropertyToXmlParam< elem_type >(static_cast<const RTT::Property< type >*>(prop)->rvalue()); }
 
#define RETURN_RTT_PROPERTY_TO_XML_PARAM(type, prop)   if(castable< type >(prop)) { return rttPropertyToXmlParam< type >(static_cast<const RTT::Property< type >*>(prop)->rvalue()); }
 

Functions

template<class T >
bool castable (const RTT::base::PropertyBase *prop)
 Determine if the RTT property can be casted into an RTT::Property<T> More...
 
XmlRpc::XmlRpcValue rttPropertyBaseToXmlParam (RTT::base::PropertyBase *prop)
 Convert an abstract RTT PropertyBase to an XmlRpc value. More...
 
template<class T >
XmlRpc::XmlRpcValue rttPropertyToXmlParam (const T &prop)
 Convert a value to an XmlRpc value. More...
 
template<class T >
XmlRpc::XmlRpcValue rttPropertyToXmlParam (const std::vector< T > &vec)
 Convert a std::vector<T> to an XmlRpc array value. More...
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam (const Eigen::VectorXd &vec)
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam (const Eigen::VectorXf &vec)
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< char > (const char &prop)
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< float > (const float &prop)
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< RTT::PropertyBag > (const RTT::PropertyBag &bag)
 Convert a PropertyBag to an XmlRpc struct value. More...
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< unsigned char > (const unsigned char &prop)
 
template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< unsigned int > (const unsigned int &prop)
 
template<class T >
bool xmlParamToProp (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< T > *prop)
 Convert an XmlRpc value into an RTT property. More...
 
template<class T >
bool xmlParamToProp (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< std::vector< T > > *prop)
 Convert an XmlRpc array value into an RTT std::vector property. More...
 
template<>
bool xmlParamToProp (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< Eigen::VectorXd > *prop)
 Convert an XmlRpc array value into an RTT Eigen::VectorXd property. More...
 
template<>
bool xmlParamToProp (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< Eigen::VectorXf > *prop)
 
bool xmlParamToProp (const XmlRpc::XmlRpcValue &xml_value, RTT::base::PropertyBase *prop_base)
 Convert an XmlRpc structure value into an abstract RTT PropertyBase. More...
 
template<>
bool xmlParamToProp< bool > (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< std::vector< bool > > *prop)
 
template<>
bool xmlParamToProp< RTT::PropertyBag > (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< RTT::PropertyBag > *prop)
 Convert an XmlRpc structure value into an RTT PropertyBag property. More...
 
template<class PropertyType >
bool xmlParamToValue (const XmlRpc::XmlRpcValue &xml_value, PropertyType &value)
 Convert an XmlRpc value to type T. More...
 

Macro Definition Documentation

#define ADD_ROSPARAM_OPERATION (   return_type_str,
  return_type,
  func 
)
Value:
this->addOperation("get"#return_type_str, &ROSParamService::get##func< return_type , RELATIVE >, this).doc("Get a " #return_type " from rosparam"); \
this->addOperation("set"#return_type_str, &ROSParamService::set##func< return_type , RELATIVE >, this).doc("Set a " #return_type " in rosparam"); \
this->addOperation("get"#return_type_str"Relative", &ROSParamService::get##func< return_type , RELATIVE >, this).doc("Get a " #return_type " from rosparam using the relative resolution policy : `relative/param`"); \
this->addOperation("set"#return_type_str"Relative", &ROSParamService::set##func< return_type , RELATIVE >, this).doc("Set a " #return_type " in rosparam using the relative resolution policy : `relative/param`"); \
this->addOperation("get"#return_type_str"Absolute", &ROSParamService::get##func< return_type , ABSOLUTE >, this).doc("Get a " #return_type " from rosparam using the absolute resolution policy : `/global/param`"); \
this->addOperation("set"#return_type_str"Absolute", &ROSParamService::set##func< return_type , ABSOLUTE >, this).doc("Set a " #return_type " in rosparam using the absolute resolution policy : `/global/param`"); \
this->addOperation("get"#return_type_str"Private", &ROSParamService::get##func< return_type , PRIVATE >, this).doc("Get a " #return_type " from rosparam using the private resolution policy : `~private/param`"); \
this->addOperation("set"#return_type_str"Private", &ROSParamService::set##func< return_type , PRIVATE >, this).doc("Set a " #return_type " in rosparam using the private resolution policy : `~private/param`"); \
this->addOperation("get"#return_type_str"ComponentPrivate", &ROSParamService::get##func< return_type , COMPONENT_PRIVATE >, this).doc("Get a " #return_type " from rosparam using the following resolution policy : `~component_name/param`"); \
this->addOperation("set"#return_type_str"ComponentPrivate", &ROSParamService::set##func< return_type , COMPONENT_PRIVATE >, this).doc("Set a " #return_type " in rosparam using the following resolution policy : `~component_name/param`"); \
this->addOperation("get"#return_type_str"ComponentRelative", &ROSParamService::get##func< return_type , COMPONENT_RELATIVE >, this).doc("Get a " #return_type " from rosparam using the following resolution policy : `component_name/param`"); \
this->addOperation("set"#return_type_str"ComponentRelative", &ROSParamService::set##func< return_type , COMPONENT_RELATIVE >, this).doc("Set a " #return_type " in rosparam using the following resolution policy : `component_name/param`"); \
this->addOperation("get"#return_type_str"ComponentAbsolute", &ROSParamService::get##func< return_type , COMPONENT_ABSOLUTE >, this).doc("Get a " #return_type " from rosparam using the following resolution policy : `/component_name/param`"); \
this->addOperation("set"#return_type_str"ComponentAbsolute", &ROSParamService::set##func< return_type , COMPONENT_ABSOLUTE >, this).doc("Set a " #return_type " in rosparam using the following resolution policy : `/component_name/param`");
bool set(const std::string &param_name, const unsigned int policy=(unsigned int) COMPONENT_PRIVATE)
bool get(const std::string &param_name, const unsigned int policy=(unsigned int) COMPONENT_PRIVATE)

Definition at line 18 of file rtt_rosparam_service.cpp.

#define RETURN_RTT_PROPERTY_CONTAINER_TO_XML_PARAM (   type,
  elem_type,
  prop 
)    if(castable< type >(prop)) { return rttPropertyToXmlParam< elem_type >(static_cast<const RTT::Property< type >*>(prop)->rvalue()); }

Definition at line 398 of file rtt_rosparam_service.cpp.

#define RETURN_RTT_PROPERTY_TO_XML_PARAM (   type,
  prop 
)    if(castable< type >(prop)) { return rttPropertyToXmlParam< type >(static_cast<const RTT::Property< type >*>(prop)->rvalue()); }

Definition at line 395 of file rtt_rosparam_service.cpp.

Function Documentation

template<class T >
bool castable ( const RTT::base::PropertyBase prop)

Determine if the RTT property can be casted into an RTT::Property<T>

Definition at line 299 of file rtt_rosparam_service.cpp.

XmlRpc::XmlRpcValue rttPropertyBaseToXmlParam ( RTT::base::PropertyBase prop)

Convert an abstract RTT PropertyBase to an XmlRpc value.

Definition at line 401 of file rtt_rosparam_service.cpp.

template<class T >
XmlRpc::XmlRpcValue rttPropertyToXmlParam ( const T &  prop)

Convert a value to an XmlRpc value.

Definition at line 305 of file rtt_rosparam_service.cpp.

template<class T >
XmlRpc::XmlRpcValue rttPropertyToXmlParam ( const std::vector< T > &  vec)

Convert a std::vector<T> to an XmlRpc array value.

Definition at line 355 of file rtt_rosparam_service.cpp.

template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam ( const Eigen::VectorXd &  vec)

Definition at line 368 of file rtt_rosparam_service.cpp.

template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam ( const Eigen::VectorXf &  vec)

Definition at line 381 of file rtt_rosparam_service.cpp.

template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< char > ( const char &  prop)

Definition at line 323 of file rtt_rosparam_service.cpp.

template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< float > ( const float &  prop)

Definition at line 311 of file rtt_rosparam_service.cpp.

Convert a PropertyBag to an XmlRpc struct value.

Definition at line 335 of file rtt_rosparam_service.cpp.

template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< unsigned char > ( const unsigned char &  prop)

Definition at line 329 of file rtt_rosparam_service.cpp.

template<>
XmlRpc::XmlRpcValue rttPropertyToXmlParam< unsigned int > ( const unsigned int &  prop)

Definition at line 317 of file rtt_rosparam_service.cpp.

template<class T >
bool xmlParamToProp ( const XmlRpc::XmlRpcValue xml_value,
RTT::Property< T > *  prop 
)

Convert an XmlRpc value into an RTT property.

Definition at line 552 of file rtt_rosparam_service.cpp.

template<class T >
bool xmlParamToProp ( const XmlRpc::XmlRpcValue xml_value,
RTT::Property< std::vector< T > > *  prop 
)

Convert an XmlRpc array value into an RTT std::vector property.

Definition at line 567 of file rtt_rosparam_service.cpp.

template<>
bool xmlParamToProp ( const XmlRpc::XmlRpcValue xml_value,
RTT::Property< Eigen::VectorXd > *  prop 
)

Convert an XmlRpc array value into an RTT Eigen::VectorXd property.

Definition at line 621 of file rtt_rosparam_service.cpp.

template<>
bool xmlParamToProp ( const XmlRpc::XmlRpcValue xml_value,
RTT::Property< Eigen::VectorXf > *  prop 
)

Definition at line 649 of file rtt_rosparam_service.cpp.

bool xmlParamToProp ( const XmlRpc::XmlRpcValue xml_value,
RTT::base::PropertyBase prop_base 
)

Convert an XmlRpc structure value into an abstract RTT PropertyBase.

Definition at line 710 of file rtt_rosparam_service.cpp.

template<>
bool xmlParamToProp< bool > ( const XmlRpc::XmlRpcValue xml_value,
RTT::Property< std::vector< bool > > *  prop 
)

Definition at line 593 of file rtt_rosparam_service.cpp.

template<>
bool xmlParamToProp< RTT::PropertyBag > ( const XmlRpc::XmlRpcValue xml_value,
RTT::Property< RTT::PropertyBag > *  prop 
)

Convert an XmlRpc structure value into an RTT PropertyBag property.

Definition at line 677 of file rtt_rosparam_service.cpp.

template<class PropertyType >
bool xmlParamToValue ( const XmlRpc::XmlRpcValue xml_value,
PropertyType &  value 
)

Convert an XmlRpc value to type T.

Definition at line 537 of file rtt_rosparam_service.cpp.



rtt_rosparam
Author(s): Ruben Smits
autogenerated on Sat Jun 8 2019 18:05:28