Drake

Classes

class  LcmPublisherSystem
 Publishes an LCM message containing information from its input port. More...
 
class  LcmSubscriberSystem
 Receives LCM messages from a given channel and outputs them to a System<double>'s port. More...
 

Functions

LcmPublisherSystemConnectLcmScope (const OutputPort< double > &src, const std::string &channel, systems::DiagramBuilder< double > *builder, drake::lcm::DrakeLcmInterface *lcm)
 Provides the ability to publish any VectorBase<double> output port to the LCM channel, using the drake::lcmt_drake_signal LCM message type, by adding an appropriate LcmPublisherSystem to the builder. More...
 

Detailed Description

Systems for publishing/subscribing to popular message passing ecosystems.

Function Documentation

◆ ConnectLcmScope()

LcmPublisherSystem * ConnectLcmScope ( const OutputPort< double > &  src,
const std::string &  channel,
systems::DiagramBuilder< double > *  builder,
drake::lcm::DrakeLcmInterface lcm 
)

Provides the ability to publish any VectorBase<double> output port to the LCM channel, using the drake::lcmt_drake_signal LCM message type, by adding an appropriate LcmPublisherSystem to the builder.

If lcm is null, then an LCM instance will be created automatically (but this is expensive, and creating multiple LCM instances in a single process should be avoided).

What it does is:

The intention is to enable logging and debugging in complex diagrams using external tools like lcm-spy. Consider using Simulator<T>::set_publish_every_time_step(), or calling the LcmPublisherSystem::set_publish_period() on the returned LcmPublisherSystem to control when the output is generated.

Precondition
src must be an OutputPort of a system that has already been added to the builder.