90 virtual swarmio::data::Variant
Get(
const std::string& path)
override;
97 virtual void Set(
const std::string& path,
const swarmio::data::Variant& value)
override;
104 virtual swarmio::data::discovery::Field
GetFieldDescriptor(
const std::string& path)
const override;
111 virtual bool CanWrite(
const std::string& name)
const noexcept
override;
118 virtual bool CanRead(
const std::string& name)
const noexcept
override;
Abstract base class for registered keys.
std::string _parameter
Parameter name.
Base class for all bridging services.
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 ¶meter, 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.