diff --git a/canopen_motor_node/src/motor_chain.cpp b/canopen_motor_node/src/motor_chain.cpp index f1188f921..cbd37f9e1 100644 --- a/canopen_motor_node/src/motor_chain.cpp +++ b/canopen_motor_node/src/motor_chain.cpp @@ -1,30 +1,9 @@ #include #include - +#include 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") {} diff --git a/socketcan_interface/include/socketcan_interface/xmlrpc_settings.h b/socketcan_interface/include/socketcan_interface/xmlrpc_settings.h new file mode 100644 index 000000000..da7a196a9 --- /dev/null +++ b/socketcan_interface/include/socketcan_interface/xmlrpc_settings.h @@ -0,0 +1,28 @@ +#ifndef SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H +#define SOCKETCAN_INTERFACE_XMLRPC_SETTINGS_H + +#include +#include "xmlrpcpp/XmlRpcValue.h" +#include +#include + +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