swarmros/include/swarmros/bridge/Node.h
Go to the documentation of this file.
1 #pragma once
2 
5 #include <ros/ros.h>
6 #include <map>
7 #include <list>
8 #include <memory>
9 
10 namespace swarmros::bridge
11 {
18  class Node final : private swarmio::profiles::MemberProfile
19  {
20  private:
21 
26  std::list<std::unique_ptr<Pylon>> _pylons;
27 
33 
34 
40 
46 
52  void PublishUpdateForNode(const swarmio::Node* node);
53 
54  public:
55 
61  Node(swarmio::Endpoint* endpoint);
62 
69  {
70  return _nodeHandle;
71  }
72 
81  void ForwardTelemetry(const std::string& source, const std::string& message, const std::string& name, bool includeInStatus);
82 
89  void ForwardEvent(const std::string& source, const std::string& message);
90 
98  void PublishEvent(const std::string& suffix, const std::string& message, const std::string& name);
99 
109  void PublishParameter(const std::string& suffix, const std::string& message, const std::string& name, const std::string& parameter, bool isWritable);
110 
118  void BridgeParameter(const std::string& name, const std::string& parameter, bool isWritable);
119 
125  virtual void NodeWasDiscovered(const swarmio::Node* node) noexcept override;
126 
132  virtual void NodeDidJoin(const swarmio::Node* node) noexcept override;
133 
139  virtual void NodeWillLeave(const swarmio::Node* node) noexcept override;
140  };
141 }
142 
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.
Service profile for swarm members.
Definition: MemberProfile.h:14
ros::NodeHandle _nodeHandle
Node handle.
ros::Publisher _uuidPublisher
The publisher for the uuid topic.
ros::NodeHandle & GetNodeHandle()
Get ROS node handle.
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
Represents a collection of standard services that can be used to bridge a ROS based member to the swa...
Node(swarmio::Endpoint *endpoint)
Construct a new Node object.
Definition: bridge/Node.cpp:13
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
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
std::list< std::unique_ptr< Pylon > > _pylons
Active bridging services.
Represents a Node the Endpoint knows about and can send messages to.
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