An extension of ParameterTarget that publishes updates as custom messages.
More...
#include <ParameterPublisher.h>
|
| ParameterPublisher (ros::NodeHandle &nodeHandle, const std::string &suffix, const std::string &message, swarmio::services::keyvalue::Service &keyvalueService, const std::string &name, const std::string ¶meter, bool isWritable) |
| Construct a new ParameterPublisher object. More...
|
|
virtual void | Set (const std::string &path, const swarmio::data::Variant &value) override |
| Set the current value of the target. More...
|
|
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 | ~ParameterTarget () |
| Destructor. More...
|
|
virtual | ~Pylon () |
| Add virtual destructor. More...
|
|
virtual void | Set (const std::string &path, const data::Variant &value)=0 |
| Set the current value of the target. More...
|
|
|
void | UpdateValue (const swarmio::data::Variant &value) |
| Update the currently latched value. More...
|
|
An extension of ParameterTarget that publishes updates as custom messages.
Definition at line 13 of file ParameterPublisher.h.
ParameterPublisher::ParameterPublisher |
( |
ros::NodeHandle & |
nodeHandle, |
|
|
const std::string & |
suffix, |
|
|
const std::string & |
message, |
|
|
swarmio::services::keyvalue::Service & |
keyvalueService, |
|
|
const std::string & |
name, |
|
|
const std::string & |
parameter, |
|
|
bool |
isWritable |
|
) |
| |
Construct a new ParameterPublisher object.
- Parameters
-
nodeHandle | Node handle |
suffix | Topic suffix |
message | Message type |
keyvalueService | Key-value service |
name | Global parameter name |
parameter | ROS parameter name |
isWritable | True if set requests should be accepted |
Definition at line 7 of file ParameterPublisher.cpp.
void ParameterPublisher::Set |
( |
const std::string & |
path, |
|
|
const swarmio::data::Variant & |
value |
|
) |
| |
|
overridevirtual |
void ParameterPublisher::UpdateValue |
( |
const swarmio::data::Variant & |
value | ) |
|
|
private |
The documentation for this class was generated from the following files: