xmlrpc_settings.h
Go to the documentation of this file.
1 #ifndef SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H
2 #define SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H
4 
6 #include "xmlrpcpp/XmlRpcValue.h"
7 #include <sstream>
8 #include <string>
9 
10 class XmlRpcSettings : public can::Settings {
11 public:
13  XmlRpcSettings(const XmlRpc::XmlRpcValue &v) : value_(v) {}
14  XmlRpcSettings& operator=(const XmlRpc::XmlRpcValue &v) { value_ = v; return *this; }
15  template<typename T> static can::SettingsConstSharedPtr create(T nh, const std::string &ns="/") {
16  std::shared_ptr<XmlRpcSettings> settings(new XmlRpcSettings);
17  nh.getParam(ns, settings->value_);
18  return settings;
19  }
20 private:
21  virtual bool getRepr(const std::string &name, std::string & repr) const {
22  const XmlRpc::XmlRpcValue *value = &value_;
23 
24  std::string n = name;
25  size_t delim_pos;
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);
31  }
32  if(value->hasMember(n)){
33  std::stringstream sstr;
34  sstr << (*value)[n];
35  repr = sstr.str();
36  return true;
37  }
38  return false;
39  }
40  XmlRpc::XmlRpcValue value_;
41 
42 };
43 
44 #endif
XmlRpcSettings
Definition: xmlrpc_settings.h:10
XmlRpcSettings::operator=
XmlRpcSettings & operator=(const XmlRpc::XmlRpcValue &v)
Definition: xmlrpc_settings.h:14
settings.h
XmlRpcSettings::getRepr
virtual bool getRepr(const std::string &name, std::string &repr) const
Definition: xmlrpc_settings.h:21
can::Settings
Definition: settings.h:11
XmlRpcSettings::value_
XmlRpc::XmlRpcValue value_
Definition: xmlrpc_settings.h:40
XmlRpcSettings::XmlRpcSettings
XmlRpcSettings(const XmlRpc::XmlRpcValue &v)
Definition: xmlrpc_settings.h:13
XmlRpcSettings::XmlRpcSettings
XmlRpcSettings()
Definition: xmlrpc_settings.h:12
XmlRpcSettings::create
static can::SettingsConstSharedPtr create(T nh, const std::string &ns="/")
Definition: xmlrpc_settings.h:15
can::SettingsConstSharedPtr
std::shared_ptr< const Settings > SettingsConstSharedPtr
Definition: settings.h:31
logging.h


socketcan_interface
Author(s): Mathias Lüdtke
autogenerated on Wed Mar 2 2022 00:52:25