1 #ifndef SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H 2 #define SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H 6 #include "xmlrpcpp/XmlRpcValue.h" 17 nh.getParam(ns, settings->value_);
21 virtual bool getRepr(
const std::string &name, std::string & repr)
const {
22 const XmlRpc::XmlRpcValue *value = &
value_;
26 while (value->getType() == XmlRpc::XmlRpcValue::TypeStruct && (delim_pos = n.find(
'/')) != std::string::npos){
27 std::string segment = n.substr(0, delim_pos);
28 if (!value->hasMember(segment))
return false;
29 value = &((*value)[segment]);
30 n.erase(0, delim_pos+1);
32 if(value->hasMember(n)){
33 std::stringstream sstr;
virtual bool getRepr(const std::string &name, std::string &repr) const
XmlRpcSettings(const XmlRpc::XmlRpcValue &v)
static can::SettingsConstSharedPtr create(T nh, const std::string &ns="/")
std::shared_ptr< const Settings > SettingsConstSharedPtr
XmlRpc::XmlRpcValue value_
XmlRpcSettings & operator=(const XmlRpc::XmlRpcValue &v)