Skip to content

Commit

Permalink
moved XmlRpcSettings to socketcan_interface
Browse files Browse the repository at this point in the history
  • Loading branch information
mathias-luedtke committed Jul 7, 2020
1 parent 805a508 commit b7d2b4e
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 22 deletions.
23 changes: 1 addition & 22 deletions canopen_motor_node/src/motor_chain.cpp
Original file line number Diff line number Diff line change
@@ -1,30 +1,9 @@

#include <canopen_motor_node/motor_chain.h>
#include <canopen_motor_node/handle_layer.h>

#include <socketcan_interface/xmlrpc_settings.h>
using namespace canopen;


class XmlRpcSettings : public Settings{
public:
XmlRpcSettings() {}
XmlRpcSettings(const XmlRpc::XmlRpcValue &v) : value_(v) {}
XmlRpcSettings& operator=(const XmlRpc::XmlRpcValue &v) { value_ = v; return *this; }
private:
virtual bool getRepr(const std::string &n, std::string & repr) const {
if(value_.hasMember(n)){
std::stringstream sstr;
sstr << const_cast< XmlRpc::XmlRpcValue &>(value_)[n]; // does not write since already existing
repr = sstr.str();
return true;
}
return false;
}
XmlRpc::XmlRpcValue value_;

};


MotorChain::MotorChain(const ros::NodeHandle &nh, const ros::NodeHandle &nh_priv) :
RosChain(nh, nh_priv), motor_allocator_("canopen_402", "canopen::MotorBase::Allocator") {}

Expand Down
28 changes: 28 additions & 0 deletions socketcan_interface/include/socketcan_interface/xmlrpc_settings.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
#ifndef SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H
#define SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H

#include <socketcan_interface/settings.h>
#include "xmlrpcpp/XmlRpcValue.h"
#include <sstream>
#include <string>

class XmlRpcSettings : public can::Settings {
public:
XmlRpcSettings() {}
XmlRpcSettings(const XmlRpc::XmlRpcValue &v) : value_(v) {}
XmlRpcSettings& operator=(const XmlRpc::XmlRpcValue &v) { value_ = v; return *this; }
private:
virtual bool getRepr(const std::string &n, std::string & repr) const {
if(value_.hasMember(n)){
std::stringstream sstr;
sstr << const_cast< XmlRpc::XmlRpcValue &>(value_)[n]; // does not write since already existing
repr = sstr.str();
return true;
}
return false;
}
XmlRpc::XmlRpcValue value_;

};

#endif

0 comments on commit b7d2b4e

Please sign in to comment.