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

Used to connect publishers to subscribers, where the subscriber wants the raw data from the publisher. More...

#include <CallbackHelper.hh>

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

Public Member Functions

 RawCallbackHelper (const boost::function< void(const std::string &)> &_cb, bool _latching=false)
 Constructor. More...
 
std::string GetMsgType () const
 Get the typename of the message that is handled. More...
 
virtual bool HandleData (const std::string &_newdata, boost::function< void(uint32_t)> _cb, uint32_t _id)
 Process new incoming data. More...
 
virtual bool HandleMessage (MessagePtr _newMsg)
 Process new incoming message. More...
 
virtual bool IsLocal () const
 Is the callback local? More...
 
- Public Member Functions inherited from gazebo::transport::CallbackHelper
 CallbackHelper (bool _latching=false)
 Constructor. More...
 
virtual ~CallbackHelper ()
 Destructor. More...
 
unsigned int GetId () const
 Get the unique ID of this callback. More...
 
bool GetLatching () const
 Is the callback latching? More...
 

Additional Inherited Members

- Protected Attributes inherited from gazebo::transport::CallbackHelper
bool latching
 True means that the callback helper will get the last published message on the topic. More...
 

Detailed Description

Used to connect publishers to subscribers, where the subscriber wants the raw data from the publisher.

Raw means that the data has not been converted into a protobuf message.

Constructor & Destructor Documentation

gazebo::transport::RawCallbackHelper::RawCallbackHelper ( const boost::function< void(const std::string &)> &  _cb,
bool  _latching = false 
)
inline

Constructor.

Parameters
[in]_cbboost function to call on incoming messages
[in]_latchingSet to true to make the callback helper latching.

Member Function Documentation

std::string gazebo::transport::RawCallbackHelper::GetMsgType ( ) const
inlinevirtual

Get the typename of the message that is handled.

Returns
String representation of the message type

Reimplemented from gazebo::transport::CallbackHelper.

virtual bool gazebo::transport::RawCallbackHelper::HandleData ( const std::string &  _newdata,
boost::function< void(uint32_t)>  _cb,
uint32_t  _id 
)
inlinevirtual

Process new incoming data.

Parameters
[in]_newdataIncoming data to be processed
Returns
true if successfully processed; false otherwise
Parameters
[in]_cbIf non-null, callback to be invoked which signals that transmission is complete.
[in]_idID associated with the message data.

Implements gazebo::transport::CallbackHelper.

virtual bool gazebo::transport::RawCallbackHelper::HandleMessage ( MessagePtr  _newMsg)
inlinevirtual

Process new incoming message.

Parameters
[in]_newMsgIncoming message to be processed
Returns
true if successfully processed; false otherwise

Implements gazebo::transport::CallbackHelper.

virtual bool gazebo::transport::RawCallbackHelper::IsLocal ( ) const
inlinevirtual

Is the callback local?

Returns
true if the callback is local, false if the callback is tied to a remote connection

Implements gazebo::transport::CallbackHelper.


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