bridge/Node.cpp
Go to the documentation of this file.
1 #include <swarmros/bridge/Node.h>
7 #include <swarmros/NodeInfo.h>
8 #include <swarmros/String.h>
9 
10 using namespace swarmros;
11 using namespace swarmros::bridge;
12 
14  : MemberProfile(endpoint)
15 {
16  // Add nodes publisher
17  _nodesPublisher = _nodeHandle.advertise<NodeInfo>("bridge/nodes", 128, false);
18 
19  // Add UUID publisher
20  _uuidPublisher = _nodeHandle.advertise<String>("bridge/uuid", 1, true);
21 
22  // Publish UUID
23  String uuidValue;
24  uuidValue.value = endpoint->GetUUID();
25  _uuidPublisher.publish(uuidValue);
26 
27  // Finish construction
29 }
30 
32 {
33  swarmros::NodeInfo message;
34  message.uuid = node->GetUUID();
35  message.name = node->GetName();
36  message.deviceClass = node->GetDeviceClass();
37  message.online = node->IsOnline();
38  _nodesPublisher.publish(message);
39 }
40 
41 void Node::NodeWasDiscovered(const swarmio::Node* node) noexcept
42 {
44 }
45 
46 void Node::NodeDidJoin(const swarmio::Node* node) noexcept
47 {
49 }
50 
51 void Node::NodeWillLeave(const swarmio::Node* node) noexcept
52 {
54 }
55 
56 void Node::ForwardTelemetry(const std::string& source, const std::string& message, const std::string& name, bool includeInStatus)
57 {
58  _pylons.push_back(std::make_unique<TelemetryForwarder>(_nodeHandle, source, message, GetTelemetryService(), name, includeInStatus));
59 }
60 
61 void Node::ForwardEvent(const std::string& source, const std::string& message)
62 {
63  _pylons.push_back(std::make_unique<EventForwarder>(_nodeHandle, source, message, GetEndpoint()));
64 }
65 
66 void Node::PublishEvent(const std::string& suffix, const std::string& message, const std::string& name)
67 {
68  _pylons.push_back(std::make_unique<EventPublisher>(_nodeHandle, suffix, message, GetEventService(), name));
69 }
70 
71 void Node::PublishParameter(const std::string& suffix, const std::string& message, const std::string& name, const std::string& parameter, bool isWritable)
72 {
73  _pylons.push_back(std::make_unique<ParameterPublisher>(_nodeHandle, suffix, message, GetKeyValueService(), name, parameter, isWritable));
74 }
75 
76 void Node::BridgeParameter(const std::string& name, const std::string& parameter, bool isWritable)
77 {
78  _pylons.push_back(std::make_unique<ParameterTarget>(_nodeHandle, GetKeyValueService(), name, parameter, isWritable));
79 }
virtual const std::string & GetDeviceClass() const =0
Get the class of the underlying device.
void PublishUpdateForNode(const swarmio::Node *node)
Publish a generic info update for a node.
Definition: bridge/Node.cpp:31
ros::Publisher _nodesPublisher
The publisher for the nodes topic.
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle _nodeHandle
Node handle.
ros::Publisher _uuidPublisher
The publisher for the uuid topic.
void FinishConstruction()
Called when the last constructor has finished its job.
Definition: Mailbox.h:46
swarmio::services::event::Service & GetEventService()
Get a reference for the Event service.
Definition: MemberProfile.h:49
void PublishEvent(const std::string &suffix, const std::string &message, const std::string &name)
Forward events from the swarm to a ROS topic.
Definition: bridge/Node.cpp:66
virtual void NodeDidJoin(const swarmio::Node *node) noexceptoverride
Called when a new Node has joined the group.
Definition: bridge/Node.cpp:46
void ForwardEvent(const std::string &source, const std::string &message)
Forward events from a topic to the swarm.
Definition: bridge/Node.cpp:61
Node(swarmio::Endpoint *endpoint)
Construct a new Node object.
Definition: bridge/Node.cpp:13
virtual const std::string & GetUUID()=0
Get the UUID of the local node.
void PublishParameter(const std::string &suffix, const std::string &message, const std::string &name, const std::string &parameter, bool isWritable)
Bridge and publish a parameter between ROS and the swarm.
Definition: bridge/Node.cpp:71
virtual void NodeWasDiscovered(const swarmio::Node *node) noexceptoverride
Called when a new Node has been discovered.
Definition: bridge/Node.cpp:41
Abstract base class for Endpoint implementations.
Definition: Endpoint.h:25
void ForwardTelemetry(const std::string &source, const std::string &message, const std::string &name, bool includeInStatus)
Forward telemetry data to the swarm.
Definition: bridge/Node.cpp:56
swarmio::services::telemetry::Service & GetTelemetryService()
Get a reference for the Telemetry service.
Definition: Profile.h:81
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void BridgeParameter(const std::string &name, const std::string &parameter, bool isWritable)
Bridge a parameter between the ROS parameter server and the swarm.
Definition: bridge/Node.cpp:76
Endpoint * GetEndpoint()
Get the associated Endpoint.
Definition: Mailbox.h:144
std::list< std::unique_ptr< Pylon > > _pylons
Active bridging services.
virtual const std::string & GetUUID() const =0
Returns the unique identifier of the node.
virtual bool IsOnline() const =0
Checks whether the Node is reachable.
virtual const std::string & GetName() const =0
Returns the (possibly non-unique) name of the node.
Represents a Node the Endpoint knows about and can send messages to.
swarmio::services::keyvalue::Service & GetKeyValueService()
Get a reference for the Key-Value service.
Definition: MemberProfile.h:59
virtual void NodeWillLeave(const swarmio::Node *node) noexceptoverride
Called when a Node signals that it will leave.
Definition: bridge/Node.cpp:51


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