pydrake.lcm

class pydrake.lcm.DrakeLcm

Bases: pydrake.lcm.DrakeLcmInterface

A wrapper around a real LCM instance.

StartReceiveThread(self: pydrake.lcm.DrakeLcm) → None

Starts the receive thread. This must be called for subscribers to receive any messages.

Precondition:
StartReceiveThread() was not called.
StopReceiveThread(self: pydrake.lcm.DrakeLcm) → None

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.
__init__(self: pydrake.lcm.DrakeLcm) → None

Constructs using LCM’s default URL (either the default hard-coded URL, or else LCM_DEFAULT_URL environment variable if it is set).

class pydrake.lcm.DrakeLcmInterface

A pure virtual interface that enables LCM to be mocked.

Publish(self: pydrake.lcm.DrakeLcmInterface, channel: unicode, buffer: str, time_sec: Optional[float] = None) → None

Publishes an LCM message on channel channel.

Parameter channel:
The channel on which to publish the message. Must not be the empty string.
Parameter data:
A buffer containing the serialized bytes of the message to publish.
Parameter data_size:
The length of @data in bytes.
Parameter time_sec:
Time in seconds when the publish event occurred. If unknown, use drake::nullopt or a default-constructed optional.
__init__

x.__init__(…) initializes x; see help(type(x)) for signature

class pydrake.lcm.DrakeMockLcm

Bases: pydrake.lcm.DrakeLcmInterface

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.

InduceSubscriberCallback(self: pydrake.lcm.DrakeMockLcm, channel: unicode, buffer: str) → None

Fakes a callback. The callback is executed by the same thread as the one calling this method.

Parameter channel:
The channel on which to publish the message.
Parameter data:
A buffer containing the serialized bytes of the message to publish.
Parameter data_size:
The length of @data in bytes.
Subscribe(self: pydrake.lcm.DrakeMockLcm, channel: unicode, handler: Callable[[str], None]) → None
__init__(self: pydrake.lcm.DrakeMockLcm) → None

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().

get_last_published_message(self: pydrake.lcm.DrakeMockLcm, channel: unicode) → str

Obtains the most recently “published” message on a particular channel. A RuntimeError will be thrown if no message was published on the provide channel.

Parameter channel:
The 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.