Public Member Functions | Static Private Member Functions | Private Attributes | List of all members
swarmros::bridge::ParameterTarget Class Reference

A Target implementation that uses the ROS parameter server. More...

#include <ParameterTarget.h>

Inheritance diagram for swarmros::bridge::ParameterTarget:
Inheritance graph
[legend]

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 &parameter, 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...
 

Detailed Description

A Target implementation that uses the ROS parameter server.

Definition at line 16 of file ParameterTarget.h.

Constructor & Destructor Documentation

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.

Parameters
nodeHandleNode handle
parameterParameter name
keyvalueServiceKey-value service
pathParameter name
isWritableTrue if can be set remotely

Definition at line 215 of file ParameterTarget.cpp.

ParameterTarget::~ParameterTarget ( )
virtual

Destructor.

Definition at line 277 of file ParameterTarget.cpp.

Member Function Documentation

bool ParameterTarget::CanRead ( const std::string &  name) const
overridevirtualnoexcept

Determines whether the value can be read.

Returns
True if Get operations are allowed

Reimplemented from swarmio::services::keyvalue::Target.

Definition at line 272 of file ParameterTarget.cpp.

bool ParameterTarget::CanWrite ( const std::string &  name) const
overridevirtualnoexcept

Determines whether the value can be written.

Returns
True if Set operations are allowed

Reimplemented from swarmio::services::keyvalue::Target.

Definition at line 267 of file ParameterTarget.cpp.

swarmio::data::Variant ParameterTarget::Get ( const std::string &  path)
overridevirtual

Get the current value of the target parameter.

Returns
swarmio::data::Variant Value

Implements swarmio::services::keyvalue::Target.

Definition at line 230 of file ParameterTarget.cpp.

swarmio::data::discovery::Field ParameterTarget::GetFieldDescriptor ( const std::string &  path) const
overridevirtual

Get the data type of the target.

Returns
swarmio::data::discovery::Type

Implements swarmio::services::keyvalue::Target.

Definition at line 255 of file ParameterTarget.cpp.

void ParameterTarget::Set ( const std::string &  path,
const swarmio::data::Variant &  value 
)
overridevirtual

Set the current value of the target.

Parameters
valueNew value

Reimplemented in swarmros::bridge::ParameterPublisher.

Definition at line 242 of file ParameterTarget.cpp.

swarmio::data::Variant ParameterTarget::VariantFromXmlRpcValue ( XmlRpc::XmlRpcValue value)
staticprivate

Convert an XmlRpc value to a variant.

Parameters
valueValue
Returns
swarmio::data::Variant

Definition at line 9 of file ParameterTarget.cpp.

XmlRpc::XmlRpcValue ParameterTarget::XmlRpcValueFromVariant ( const swarmio::data::Variant &  value)
staticprivate

Convert a variant to an XmlRpc value.

Parameters
valueValue
Returns
XmlRpc::XmlRpcValue

Definition at line 99 of file ParameterTarget.cpp.

Member Data Documentation

bool swarmros::bridge::ParameterTarget::_isWritable
private

True if the property can be set.

Definition at line 48 of file ParameterTarget.h.

swarmio::services::keyvalue::Service& swarmros::bridge::ParameterTarget::_keyvalueService
private

Key-value service.

Definition at line 36 of file ParameterTarget.h.

ros::NodeHandle swarmros::bridge::ParameterTarget::_nodeHandle
private

Node handle.

Definition at line 24 of file ParameterTarget.h.

std::string swarmros::bridge::ParameterTarget::_parameter
private

Parameter name.

Definition at line 30 of file ParameterTarget.h.

std::string swarmros::bridge::ParameterTarget::_path
private

Discoverable keyvalue name.

Definition at line 42 of file ParameterTarget.h.

swarmio::data::Variant swarmros::bridge::ParameterTarget::_value
private

Current value.

Definition at line 54 of file ParameterTarget.h.


The documentation for this class was generated from the following files:


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