All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | List of all members
gazebo::transport::Node Class Reference

A node can advertise and subscribe topics, publish on advertised topics and listen to subscribed topics. More...

#include <transport/transport.hh>

Inheritance diagram for gazebo::transport::Node:
Inheritance graph
[legend]

Public Member Functions

 Node ()
 Constructor.
 
virtual ~Node ()
 Destructor.
 
template<typename M >
transport::PublisherPtr Advertise (const std::string &_topic, unsigned int _queueLimit=1000)
 Adverise a topic.
 
std::string DecodeTopicName (const std::string &_topic)
 Decode a topic name.
 
std::string EncodeTopicName (const std::string &_topic)
 Encode a topic name.
 
void Fini ()
 Finalize the node.
 
unsigned int GetId () const
 Get the unique ID of the node.
 
std::string GetMsgType (const std::string &_topic) const
 Get the message type for a topic.
 
std::string GetTopicNamespace () const
 Get the topic namespace for this node.
 
bool HandleData (const std::string &_topic, const std::string &_msg)
 Handle incoming data.
 
bool HasLatchedSubscriber (const std::string &_topic) const
 Return true if a subscriber on a specific topic is latched.
 
void Init (const std::string &_space="")
 Init the node.
 
void InsertLatchedMsg (const std::string &_topic, const std::string &_msg)
 Add a latched message to the node for publication.
 
void ProcessIncoming ()
 Process incoming messages.
 
void ProcessPublishers ()
 Process all publishers, which has each publisher send it's most recent message over the wire.
 
void RemoveCallback (const std::string &_topic, unsigned int _id)
 
template<typename M , typename T >
SubscriberPtr Subscribe (const std::string &_topic, void(T::*_fp)(const M const *&), T *_obj, bool _latching=false)
 Subscribe to a topic using a class method as the callback.
 
template<typename M >
SubscriberPtr Subscribe (const std::string &_topic, void(*_fp)(const M const *&), bool _latching=false)
 Subscribe to a topic using a bare function as the callback.
 
template<typename T >
SubscriberPtr Subscribe (const std::string &_topic, void(T::*_fp)(const std::string &), T *_obj, bool _latching=false)
 Subscribe to a topic using a class method as the callback.
 
SubscriberPtr Subscribe (const std::string &_topic, void(*_fp)(const std::string &), bool _latching=false)
 Subscribe to a topic using a bare function as the callback.
 

Detailed Description

A node can advertise and subscribe topics, publish on advertised topics and listen to subscribed topics.

Constructor & Destructor Documentation

gazebo::transport::Node::Node ( )

Constructor.

virtual gazebo::transport::Node::~Node ( )
virtual

Destructor.

Member Function Documentation

template<typename M >
transport::PublisherPtr gazebo::transport::Node::Advertise ( const std::string &  _topic,
unsigned int  _queueLimit = 1000 
)
inline

Adverise a topic.

Parameters
[in]_topicThe topic to advertise
[in]_queueLimitThe maximum number of outgoing messages to queue for delivery
Returns
Pointer to new publisher object

References DecodeTopicName(), and SingletonT< T >::Instance().

std::string gazebo::transport::Node::DecodeTopicName ( const std::string &  _topic)

Decode a topic name.

Parameters
[in]Theencoded name
Returns
The decoded name

Referenced by Advertise(), and Subscribe().

std::string gazebo::transport::Node::EncodeTopicName ( const std::string &  _topic)

Encode a topic name.

Parameters
[in]Thedecoded name
Returns
The encoded name
void gazebo::transport::Node::Fini ( )

Finalize the node.

unsigned int gazebo::transport::Node::GetId ( ) const

Get the unique ID of the node.

Returns
The unique ID of the node

Referenced by Subscribe().

std::string gazebo::transport::Node::GetMsgType ( const std::string &  _topic) const

Get the message type for a topic.

Parameters
[in]_topicThe topic
Returns
The message type
std::string gazebo::transport::Node::GetTopicNamespace ( ) const

Get the topic namespace for this node.

Returns
The namespace
bool gazebo::transport::Node::HandleData ( const std::string &  _topic,
const std::string &  _msg 
)

Handle incoming data.

Parameters
[in]_topicTopic for which the data was received
[in]_msgThe message that was received
Returns
true if the message was handled successfully, false otherwise
bool gazebo::transport::Node::HasLatchedSubscriber ( const std::string &  _topic) const

Return true if a subscriber on a specific topic is latched.

Parameters
[in]_topicName of the topic to check.
Returns
True if a latched subscriber exists.
void gazebo::transport::Node::Init ( const std::string &  _space = "")

Init the node.

Parameters
[in]_spaceSet the global namespace of all topics. If left blank, the topic will initialize to the first namespace on the Master
void gazebo::transport::Node::InsertLatchedMsg ( const std::string &  _topic,
const std::string &  _msg 
)

Add a latched message to the node for publication.

This is called when a subscription is connected to a publication.

Parameters
[in]_topicName of the topic to publish data on.
[in]_msgThe message to publish.
void gazebo::transport::Node::ProcessIncoming ( )

Process incoming messages.

void gazebo::transport::Node::ProcessPublishers ( )

Process all publishers, which has each publisher send it's most recent message over the wire.

This is for internal use only

void gazebo::transport::Node::RemoveCallback ( const std::string &  _topic,
unsigned int  _id 
)
template<typename M , typename T >
SubscriberPtr gazebo::transport::Node::Subscribe ( const std::string &  _topic,
void(T::*)(const M const *&)  _fp,
T *  _obj,
bool  _latching = false 
)
inline

Subscribe to a topic using a class method as the callback.

Parameters
[in]_topicThe topic to subscribe to
[in]_fpClass method to be called on receipt of new message
[in]_objClass instance to be used on receipt of new message
[in]_latchingIf true, latch latest incoming message; otherwise don't latch
Returns
Pointer to new Subscriber object

References DecodeTopicName(), GetId(), SingletonT< T >::Instance(), and gazebo::transport::Subscriber::SetCallbackId().

template<typename M >
SubscriberPtr gazebo::transport::Node::Subscribe ( const std::string &  _topic,
void(*)(const M const *&)  _fp,
bool  _latching = false 
)
inline

Subscribe to a topic using a bare function as the callback.

Parameters
[in]_topicThe topic to subscribe to
[in]_fpFunction to be called on receipt of new message
[in]_latchingIf true, latch latest incoming message; otherwise don't latch
Returns
Pointer to new Subscriber object

References DecodeTopicName(), GetId(), SingletonT< T >::Instance(), and gazebo::transport::Subscriber::SetCallbackId().

template<typename T >
SubscriberPtr gazebo::transport::Node::Subscribe ( const std::string &  _topic,
void(T::*)(const std::string &)  _fp,
T *  _obj,
bool  _latching = false 
)
inline

Subscribe to a topic using a class method as the callback.

Parameters
[in]_topicThe topic to subscribe to
[in]_fpClass method to be called on receipt of new message
[in]_objClass instance to be used on receipt of new message
[in]_latchingIf true, latch latest incoming message; otherwise don't latch
Returns
Pointer to new Subscriber object

References DecodeTopicName(), GetId(), gazebo::transport::SubscribeOptions::Init(), SingletonT< T >::Instance(), and gazebo::transport::Subscriber::SetCallbackId().

SubscriberPtr gazebo::transport::Node::Subscribe ( const std::string &  _topic,
void(*)(const std::string &)  _fp,
bool  _latching = false 
)
inline

Subscribe to a topic using a bare function as the callback.

Parameters
[in]_topicThe topic to subscribe to
[in]_fpFunction to be called on receipt of new message
[in]_latchingIf true, latch latest incoming message; otherwise don't latch
Returns
Pointer to new Subscriber object

References DecodeTopicName(), GetId(), gazebo::transport::SubscribeOptions::Init(), SingletonT< T >::Instance(), and gazebo::transport::Subscriber::SetCallbackId().


The documentation for this class was generated from the following file: