Classes | Defines | 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 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 >

Defines

#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>
XmlRpc::XmlRpcValue rttPropertyBaseToXmlParam (RTT::base::PropertyBase *prop)
 Convert an abstract RTT PropertyBase to an XmlRpc value.
template<class T >
XmlRpc::XmlRpcValue rttPropertyToXmlParam (const T &prop)
 Convert a value to an XmlRpc value.
template<class T >
XmlRpc::XmlRpcValue rttPropertyToXmlParam (const std::vector< T > &vec)
 Convert a std::vector<T> to an XmlRpc array value.
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.
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.
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.
template<>
bool xmlParamToProp (const XmlRpc::XmlRpcValue &xml_value, RTT::Property< Eigen::VectorXd > *prop)
 Convert an XmlRpc array value into an RTT Eigen::VectorXd property.
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.
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.
template<class PropertyType >
bool xmlParamToValue (const XmlRpc::XmlRpcValue &xml_value, PropertyType &value)
 Convert an XmlRpc value to type T.

Define Documentation

#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 298 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 295 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 199 of file rtt_rosparam_service.cpp.

Convert an abstract RTT PropertyBase to an XmlRpc value.

Definition at line 301 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 205 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 255 of file rtt_rosparam_service.cpp.

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

Definition at line 268 of file rtt_rosparam_service.cpp.

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

Definition at line 281 of file rtt_rosparam_service.cpp.

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

Definition at line 223 of file rtt_rosparam_service.cpp.

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

Definition at line 211 of file rtt_rosparam_service.cpp.

Convert a PropertyBag to an XmlRpc struct value.

Definition at line 235 of file rtt_rosparam_service.cpp.

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

Definition at line 229 of file rtt_rosparam_service.cpp.

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

Definition at line 217 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 452 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 467 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 521 of file rtt_rosparam_service.cpp.

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

Definition at line 549 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 608 of file rtt_rosparam_service.cpp.

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

Definition at line 493 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 577 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 437 of file rtt_rosparam_service.cpp.



rtt_rosparam
Author(s): Ruben Smits
autogenerated on Wed Sep 16 2015 06:59:02