ParameterPublisher.cpp
Go to the documentation of this file.
3 
4 using namespace swarmros;
5 using namespace swarmros::bridge;
6 
7 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)
8  : ParameterTarget(nodeHandle, keyvalueService, name, parameter, isWritable)
9 {
10  // Register schema
12 
13  // Create publisher
14  ros::AdvertiseOptions options("bridge/parameters/" + suffix, 1, _serializer->GetHash(), _serializer->GetFullName(), _serializer->GetCanonicalDefinition());
15  options.latch = true;
16  _publisher = nodeHandle.advertise(options);
17 
18  // Update value
19  UpdateValue(Get(name));
20 }
21 
22 void ParameterPublisher::Set(const std::string& path, const swarmio::data::Variant& value)
23 {
24  // Call superclass implementation
25  ParameterTarget::Set(path, value);
26 
27  // Send upate
28  UpdateValue(value);
29 }
30 
31 void ParameterPublisher::UpdateValue(const swarmio::data::Variant& value)
32 {
33  // Construct message
35 
36  // Publish message
38 }
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.
The Key-Value Service is responsible for getting and setting named values.
void publish(const boost::shared_ptr< M > &message) const
const std::string & GetCanonicalDefinition() const
Get the canonical definition of the message.
const std::string & GetHash() const
Get the MD5 hash of the message definition file.
static const MessageSerializer & MessageSerializerForType(const std::string &type, const std::string &parentPackage)
Look up or build a reader for a message type.
A Target implementation that uses the ROS parameter server.
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.
ros::Publisher _publisher
Publisher.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
const introspection::MessageSerializer * _serializer
Serializer.
virtual void Set(const std::string &path, const swarmio::data::Variant &value) override
Set the current value of the target.
void UpdateValue(const swarmio::data::Variant &value)
Update the currently latched value.
virtual const std::string & GetFullName() const override
Get the fully qualified name for the type behind the serializer.
VariantMessage implements an interface with the ROS type system to send and receive messages of any k...


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