Drake
DrakeMockLcm Class Reference

A mock LCM instance. More...

#include <drake/lcm/drake_mock_lcm.h>

Inheritance diagram for DrakeMockLcm:
[legend]
Collaboration diagram for DrakeMockLcm:
[legend]

Public Member Functions

 DrakeMockLcm ()
 A constructor that creates a DrakeMockLcm with loopback disabled, i.e., a call to Publish() will not result in subscriber callback functions being executed. More...
 
void EnableLoopBack ()
 Enables loopback behavior. More...
 
void StartReceiveThread () override
 Starts the receive thread. More...
 
void StopReceiveThread () override
 Stops the receive thread. More...
 
void Publish (const std::string &channel, const void *data, int data_size, double time_sec=0) override
 Publishes an LCM message on channel channel. More...
 
template<typename T >
DecodeLastPublishedMessageAs (const std::string &channel) const
 Obtains the most recently "published" message on a particular channel. More...
 
const std::vector< uint8_t > & get_last_published_message (const std::string &channel) const
 Obtains the most recently "published" message on a particular channel. More...
 
void Subscribe (const std::string &channel, DrakeLcmMessageHandlerInterface *handler) override
 Creates a subscription. More...
 
void InduceSubscriberCallback (const std::string &channel, const void *data, int data_size)
 Fakes a callback. More...
 
Does not allow copy, move, or assignment
 DrakeMockLcm (const DrakeMockLcm &)=delete
 
DrakeMockLcmoperator= (const DrakeMockLcm &)=delete
 
 DrakeMockLcm (DrakeMockLcm &&)=delete
 
DrakeMockLcmoperator= (DrakeMockLcm &&)=delete
 
- Public Member Functions inherited from DrakeLcmInterface
 DrakeLcmInterface ()=default
 
virtual ~DrakeLcmInterface ()=default
 
virtual void DispatchMessageAndAdvanceLog (double)
 Only used for supporting Lcm log playback. More...
 
virtual double GetNextMessageTime () const
 Only used for supporting Lcm log playback. More...
 
 DrakeLcmInterface (const DrakeLcmInterface &)=delete
 
DrakeLcmInterfaceoperator= (const DrakeLcmInterface &)=delete
 
 DrakeLcmInterface (DrakeLcmInterface &&)=delete
 
DrakeLcmInterfaceoperator= (DrakeLcmInterface &&)=delete
 

Detailed Description

A mock LCM instance.

This does not actually publish or subscribe to LCM messages. It contains additional methods for accessing the most recent message that was "published," and faking a callback.

Constructor & Destructor Documentation

DrakeMockLcm ( const DrakeMockLcm )
delete
DrakeMockLcm ( DrakeMockLcm &&  )
delete

A constructor that creates a DrakeMockLcm with loopback disabled, i.e., a call to Publish() will not result in subscriber callback functions being executed.

To enable loopback behavior, call EnableLoopBack().

Member Function Documentation

T DecodeLastPublishedMessageAs ( const std::string &  channel) const
inline

Obtains the most recently "published" message on a particular channel.

This method automatically decodes the message into an LCM message whose type is specified by the template type. Throws a std::runtime_error exception if no LCM message was published on the provided channel or if the message failed to be decoded by the provided LCM message type.

Template Parameters
TThe LCM message type.
Parameters
[in]channelthe LCM channel for which the last published message is returned.
Returns
the decoded most recently transmitted LCM message on the provided channel.

Here is the call graph for this function:

void EnableLoopBack ( )
inline

Enables loopback behavior.

With loopback enabled, a call to Publish() will result in subscriber callback functions being called. Without loopback enabled, the only way to induce a call to a subscriber's callback function is through InduceSubscriberCallback().

Here is the call graph for this function:

const std::vector< uint8_t > & get_last_published_message ( const std::string &  channel) const

Obtains the most recently "published" message on a particular channel.

A std::runtime_error will be thrown if no message was published on the provide channel.

Parameters
[in]channelThe channel on which the LCM message was published.
Returns
A reference to a vector containing the serialized bytes of the LCM message that was previously published on channel channel.
Precondition
A message was previously published on channel channel.

Here is the caller graph for this function:

void InduceSubscriberCallback ( const std::string &  channel,
const void *  data,
int  data_size 
)

Fakes a callback.

This will only work if StartReceivedThread() was already called, otherwise this method will do nothing. The callback is executed by the same thread as the one calling this method.

Parameters
[in]channelThe channel on which to publish the message.
[in]dataA buffer containing the serialized bytes of the message to publish.
[in]data_sizeThe length of in bytes.

Here is the caller graph for this function:

DrakeMockLcm& operator= ( DrakeMockLcm &&  )
delete
DrakeMockLcm& operator= ( const DrakeMockLcm )
delete
void Publish ( const std::string &  channel,
const void *  data,
int  data_size,
double  time_sec = 0 
)
overridevirtual

Publishes an LCM message on channel channel.

Parameters
[in]channelThe channel on which to publish the message.
[in]dataA buffer containing the serialized bytes of the message to publish.
[in]data_sizeThe length of in bytes.
[in]time_secTime in seconds when the publish event occurred. Note that this argument is only used when generating a Lcm log.

Implements DrakeLcmInterface.

Here is the call graph for this function:

Here is the caller graph for this function:

void StartReceiveThread ( )
overridevirtual

Starts the receive thread.

This must be called for subscribers to receive any messages.

Precondition
StartReceiveThread() was not called.

Implements DrakeLcmInterface.

Here is the caller graph for this function:

void StopReceiveThread ( )
overridevirtual

Stops the receive thread.

This must be called prior to any subscribers being destroyed. Note that the receive thread will be automatically stopped by this class's destructor, so usage of this method will be extremely rare. It will only be needed if this class's instance and the subscribers to LCM channels are owned by different classes. In such a scenario, this method can be used to ensure the receive thread is destroyed before the subscribers are destroyed.

Precondition
StartReceiveThread() was called.

Implements DrakeLcmInterface.

Here is the caller graph for this function:

void Subscribe ( const std::string &  channel,
DrakeLcmMessageHandlerInterface handler 
)
overridevirtual

Creates a subscription.

Only one subscription per channel name is permitted. A std::runtime_error is thrown if more than one subscription to the same channel name is attempted.

Implements DrakeLcmInterface.

Here is the caller graph for this function:


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