26 std::list<std::unique_ptr<Pylon>>
_pylons;
81 void ForwardTelemetry(
const std::string& source,
const std::string&
message,
const std::string& name,
bool includeInStatus);
89 void ForwardEvent(
const std::string& source,
const std::string& message);
98 void PublishEvent(
const std::string& suffix,
const std::string& message,
const std::string& name);
109 void PublishParameter(
const std::string& suffix,
const std::string& message,
const std::string& name,
const std::string& parameter,
bool isWritable);
118 void BridgeParameter(
const std::string& name,
const std::string& parameter,
bool isWritable);
void PublishUpdateForNode(const swarmio::Node *node)
Publish a generic info update for a node.
ros::Publisher _nodesPublisher
The publisher for the nodes topic.
Service profile for swarm members.
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.
virtual void NodeDidJoin(const swarmio::Node *node) noexceptoverride
Called when a new Node has joined the group.
void ForwardEvent(const std::string &source, const std::string &message)
Forward events from a topic to the swarm.
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.
void PublishParameter(const std::string &suffix, const std::string &message, const std::string &name, const std::string ¶meter, bool isWritable)
Bridge and publish a parameter between ROS and the swarm.
virtual void NodeWasDiscovered(const swarmio::Node *node) noexceptoverride
Called when a new Node has been discovered.
Abstract base class for Endpoint implementations.
void ForwardTelemetry(const std::string &source, const std::string &message, const std::string &name, bool includeInStatus)
Forward telemetry data to the swarm.
void BridgeParameter(const std::string &name, const std::string ¶meter, bool isWritable)
Bridge a parameter between the ROS parameter server and the swarm.
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.