A Target implementation that uses the ROS parameter server. More...
#include <ParameterTarget.h>
Public Member Functions | |
virtual bool | CanRead (const std::string &name) const noexceptoverride |
Determines whether the value can be read. More... | |
virtual bool | CanWrite (const std::string &name) const noexceptoverride |
Determines whether the value can be written. More... | |
virtual swarmio::data::Variant | Get (const std::string &path) override |
Get the current value of the target parameter. More... | |
virtual swarmio::data::discovery::Field | GetFieldDescriptor (const std::string &path) const override |
Get the data type of the target. More... | |
ParameterTarget (ros::NodeHandle &nodeHandle, swarmio::services::keyvalue::Service &keyvalueService, const std::string &name, const std::string ¶meter, bool isWritable) | |
Construct a new ParameterTarget object. More... | |
virtual void | Set (const std::string &path, const swarmio::data::Variant &value) override |
Set the current value of the target. More... | |
virtual | ~ParameterTarget () |
Destructor. More... | |
Public Member Functions inherited from swarmros::bridge::Pylon | |
virtual | ~Pylon () |
Add virtual destructor. More... | |
Public Member Functions inherited from swarmio::services::keyvalue::Target | |
virtual void | Set (const std::string &path, const data::Variant &value)=0 |
Set the current value of the target. More... | |
Static Private Member Functions | |
static swarmio::data::Variant | VariantFromXmlRpcValue (XmlRpc::XmlRpcValue &value) |
Convert an XmlRpc value to a variant. More... | |
static XmlRpc::XmlRpcValue | XmlRpcValueFromVariant (const swarmio::data::Variant &value) |
Convert a variant to an XmlRpc value. More... | |
Private Attributes | |
bool | _isWritable |
True if the property can be set. More... | |
swarmio::services::keyvalue::Service & | _keyvalueService |
Key-value service. More... | |
ros::NodeHandle | _nodeHandle |
Node handle. More... | |
std::string | _parameter |
Parameter name. More... | |
std::string | _path |
Discoverable keyvalue name. More... | |
swarmio::data::Variant | _value |
Current value. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from swarmros::bridge::Pylon | |
Pylon () | |
Mark as abstract. More... | |
A Target implementation that uses the ROS parameter server.
Definition at line 16 of file ParameterTarget.h.
ParameterTarget::ParameterTarget | ( | ros::NodeHandle & | nodeHandle, |
swarmio::services::keyvalue::Service & | keyvalueService, | ||
const std::string & | name, | ||
const std::string & | parameter, | ||
bool | isWritable | ||
) |
Construct a new ParameterTarget object.
nodeHandle | Node handle |
parameter | Parameter name |
keyvalueService | Key-value service |
path | Parameter name |
isWritable | True if can be set remotely |
Definition at line 215 of file ParameterTarget.cpp.
|
virtual |
Destructor.
Definition at line 277 of file ParameterTarget.cpp.
|
overridevirtualnoexcept |
Determines whether the value can be read.
Reimplemented from swarmio::services::keyvalue::Target.
Definition at line 272 of file ParameterTarget.cpp.
|
overridevirtualnoexcept |
Determines whether the value can be written.
Reimplemented from swarmio::services::keyvalue::Target.
Definition at line 267 of file ParameterTarget.cpp.
|
overridevirtual |
Get the current value of the target parameter.
Implements swarmio::services::keyvalue::Target.
Definition at line 230 of file ParameterTarget.cpp.
|
overridevirtual |
Get the data type of the target.
Implements swarmio::services::keyvalue::Target.
Definition at line 255 of file ParameterTarget.cpp.
|
overridevirtual |
Set the current value of the target.
value | New value |
Reimplemented in swarmros::bridge::ParameterPublisher.
Definition at line 242 of file ParameterTarget.cpp.
|
staticprivate |
Convert an XmlRpc value to a variant.
value | Value |
Definition at line 9 of file ParameterTarget.cpp.
|
staticprivate |
Convert a variant to an XmlRpc value.
value | Value |
Definition at line 99 of file ParameterTarget.cpp.
|
private |
True if the property can be set.
Definition at line 48 of file ParameterTarget.h.
|
private |
Key-value service.
Definition at line 36 of file ParameterTarget.h.
|
private |
Node handle.
Definition at line 24 of file ParameterTarget.h.
|
private |
Parameter name.
Definition at line 30 of file ParameterTarget.h.
|
private |
Discoverable keyvalue name.
Definition at line 42 of file ParameterTarget.h.
|
private |
Current value.
Definition at line 54 of file ParameterTarget.h.