ParameterTarget.h
Go to the documentation of this file.
1 #pragma once
2 
6 #include <ros/ros.h>
7 #include <xmlrpcpp/XmlRpcValue.h>
8 
9 namespace swarmros::bridge
10 {
17  {
18  private:
19 
25 
30  std::string _parameter;
31 
37 
42  std::string _path;
43 
49 
54  swarmio::data::Variant _value;
55 
62  static swarmio::data::Variant VariantFromXmlRpcValue(XmlRpc::XmlRpcValue& value);
63 
70  static XmlRpc::XmlRpcValue XmlRpcValueFromVariant(const swarmio::data::Variant& value);
71 
72  public:
73 
83  ParameterTarget(ros::NodeHandle& nodeHandle, swarmio::services::keyvalue::Service& keyvalueService, const std::string& name, const std::string& parameter, bool isWritable);
84 
90  virtual swarmio::data::Variant Get(const std::string& path) override;
91 
97  virtual void Set(const std::string& path, const swarmio::data::Variant& value) override;
98 
104  virtual swarmio::data::discovery::Field GetFieldDescriptor(const std::string& path) const override;
105 
111  virtual bool CanWrite(const std::string& name) const noexcept override;
112 
118  virtual bool CanRead(const std::string& name) const noexcept override;
119 
124  virtual ~ParameterTarget();
125  };
126 }
127 
Abstract base class for registered keys.
Definition: Target.h:12
std::string _parameter
Parameter name.
Base class for all bridging services.
Definition: Pylon.h:9
swarmio::data::Variant _value
Current value.
The Key-Value Service is responsible for getting and setting named values.
ros::NodeHandle _nodeHandle
Node handle.
virtual swarmio::data::discovery::Field GetFieldDescriptor(const std::string &path) const override
Get the data type of the target.
static XmlRpc::XmlRpcValue XmlRpcValueFromVariant(const swarmio::data::Variant &value)
Convert a variant to an XmlRpc value.
A Target implementation that uses the ROS parameter server.
bool _isWritable
True if the property can be set.
virtual swarmio::data::Variant Get(const std::string &path) override
Get the current value of the target parameter.
virtual void Set(const std::string &path, const swarmio::data::Variant &value) override
Set the current value of the target.
ParameterTarget(ros::NodeHandle &nodeHandle, swarmio::services::keyvalue::Service &keyvalueService, const std::string &name, const std::string &parameter, bool isWritable)
Construct a new ParameterTarget object.
virtual ~ParameterTarget()
Destructor.
virtual bool CanWrite(const std::string &name) const noexceptoverride
Determines whether the value can be written.
swarmio::services::keyvalue::Service & _keyvalueService
Key-value service.
virtual bool CanRead(const std::string &name) const noexceptoverride
Determines whether the value can be read.
static swarmio::data::Variant VariantFromXmlRpcValue(XmlRpc::XmlRpcValue &value)
Convert an XmlRpc value to a variant.
std::string _path
Discoverable keyvalue name.


swarmros
Author(s):
autogenerated on Fri Apr 3 2020 03:42:48