7 #include <swarmros/NodeInfo.h> 8 #include <swarmros/String.h> 14 : MemberProfile(endpoint)
24 uuidValue.value = endpoint->
GetUUID();
25 _uuidPublisher.publish(uuidValue);
71 void Node::PublishParameter(
const std::string& suffix,
const std::string&
message,
const std::string& name,
const std::string& parameter,
bool isWritable)
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.
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.
swarmio::services::event::Service & GetEventService()
Get a reference for the Event service.
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.
Node(swarmio::Endpoint *endpoint)
Construct a new Node object.
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 ¶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.
swarmio::services::telemetry::Service & GetTelemetryService()
Get a reference for the Telemetry service.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void BridgeParameter(const std::string &name, const std::string ¶meter, bool isWritable)
Bridge a parameter between the ROS parameter server and the swarm.
Endpoint * GetEndpoint()
Get the associated Endpoint.
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.
virtual void NodeWillLeave(const swarmio::Node *node) noexceptoverride
Called when a Node signals that it will leave.