pydrake.systems.lcm

pydrake.systems.lcm.ApplyLcmBusConfig(lcm_buses: dict[str, Optional[pydrake.lcm.DrakeLcmParams]], builder: pydrake.systems.framework.DiagramBuilder) pydrake.systems.lcm.LcmBuses

Given LCM bus names and (nullable) parameters, adds an LcmInterfaceSystem within the given diagram builder for each bus, and returns an LcmBuses object that provides access to the drake::lcm::DrakeLcmInterface objects that were created.

Because the interfaces live within the builder (and so eventually, the diagram), the diagram will pump the interfaces when it’s used with a simulator. Refer to the LcmInterfaceSystem documentation for details.

The interface pointers remain owned by the builder; the LcmBuses object merely aliases into the builder (and then eventually, the diagram).

As a special case, the user can opt-out of LCM either by passing nullopt as the drake::lcm::DrakeLcmParams, or by setting the URL within the DrakeLcmParams to LcmBuses::kLcmUrlMemqNull. In that case, only a drake::lcm::DrakeLcmInterface object will be created (not a full LcmInterfaceSystem), and the LCM messages will not be pumped.

Parameter lcm_buses:

A map of {bus_name: params} for LCM transceivers, to be used by drivers, sensors, etc.

class pydrake.systems.lcm.LcmBuses
__init__(self: pydrake.systems.lcm.LcmBuses) None

Constructs an empty mapping.

Add(self: pydrake.systems.lcm.LcmBuses, bus_name: str, bus: pydrake.lcm.DrakeLcmInterface) None

Adds a bus. Throws if the bus is nullptr, or if there was already a bus of the same name.

Find(self: pydrake.systems.lcm.LcmBuses, description_of_caller: str, bus_name: str) pydrake.lcm.DrakeLcmInterface

Finds the bus of the given name, or throws if there is no such bus.

The return value is an alias into memory owned elsewhere (typically by a DiagramBuilder or a Diagram) and is never nullptr.

Parameter description_of_caller:

is a noun phrase that will be used when creating an error message. A typical value would be something like “Camera 5”, “Robot controller”, “The default visualizer”, or etc.

GetAllBusNames(self: pydrake.systems.lcm.LcmBuses) list[str]

Returns a list of all known bus_name keys.

kLcmUrlMemqNull = 'memq://null'
size(self: pydrake.systems.lcm.LcmBuses) int

Returns the total number of buses.

class pydrake.systems.lcm.LcmInterfaceSystem

Bases: pydrake.systems.framework.LeafSystem

LcmInterfaceSystem acts within a Diagram to allow LcmSubscriberSystem instances to receive data from the network during a simulation. When its parent Diagram is run via the Simulator, the LcmSubscriberSystem sources will output new values based on new data received over LCM.

This System has no inputs nor outputs nor state nor parameters; it declares only an update event that pumps LCM messages into their subscribers iff the LCM stack has message(s) waiting. The subscribers will then update their outputs using their own declared events.

Note that because this class implements DrakeLcmInterface, any subscriber registered on that interface will be serviced during simulation, not just `LcmSubscriberSystem`s.

Click to expand C++ code...
{cpp}
DiagramBuilder<double> builder;
auto lcm = builder.AddSystem<LcmInterfaceSystem>();
auto subscriber = builder.AddSystem(
    LcmSubscriberSystem::Make<lcmt_drake_signal>("channel", lcm));

Warning

In C++, this class inherits both LeafSystem and DrakeLcmInterface. However, in Python, this only inherits from LeafSystem since our fork of pybind11 does not support multiple inheritance. Additionally, it only exposes the constructor accepting a DrakeLcmInterface, so that it can still be used in interface code.

__init__(self: pydrake.systems.lcm.LcmInterfaceSystem, lcm: pydrake.lcm.DrakeLcmInterface) None

Constructs using the given LCM service. The pointer is aliased by this class and must remain valid for the lifetime of this object. Users MUST NOT start the receive thread on this object.

get_lcm_url(self: pydrake.systems.lcm.LcmInterfaceSystem) str

Returns a URL describing the transport of this LCM interface.

When the URL refers to a transport offered by LCM itself (e.g., memq or udpm), then this function must return the conventional URL spelling. If the implementation of DrakeLcmInterface is using a non-standard back end, the result implementation-defined.

In either case, it is always formatted using URI syntax rules per the RFC(s).

HandleSubscriptions(self: pydrake.systems.lcm.LcmInterfaceSystem, timeout_millis: int) int

Invokes the HandlerFunction callbacks for all subscriptions’ pending messages. If timeout_millis is >0, blocks for up to that long until at least one message is handled.

Returns

the number of messages handled, or 0 on timeout.

Raises

RuntimeError when a subscribed handler throws.

class pydrake.systems.lcm.LcmPublisherSystem

Bases: pydrake.systems.framework.LeafSystem

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.systems.lcm.LcmPublisherSystem, channel: str, serializer: pydrake.systems.lcm.SerializerInterface, lcm: pydrake.systems.lcm.LcmInterfaceSystem, publish_period: float = 0.0, publish_offset: float = 0.0) -> None

A constructor for an LcmPublisherSystem that takes LCM message objects on its sole abstract-valued input port. The LCM message type is determined by the provided serializer. Will publish on forced events and either periodic or per-step events, as determined by publish_period.

Parameter channel:

The LCM channel on which to publish.

Parameter serializer:

The serializer that converts between byte vectors and LCM message objects. Cannot be null.

Parameter lcm:

A pointer to the LCM subsystem to use, which must remain valid for the lifetime of this object. If null, a drake::lcm::DrakeLcm object is allocated and maintained internally, but see the note in the class comments.

Parameter publish_period:

Period that messages will be published (optional). If the publish period is zero, LcmPublisherSystem will use per-step publishing instead; see LeafSystem::DeclarePerStepPublishEvent().

Parameter publish_offset:

Offset that messages will be published (optional), in seconds. This adds a phase-shift delay to periodic publish events.

Precondition:

publish_period is non-negative.

Precondition:

publish_offset is finite and non-negative.

Precondition:

publish_offset is set to zero when the publish_period is zero.

  1. __init__(self: pydrake.systems.lcm.LcmPublisherSystem, channel: str, serializer: pydrake.systems.lcm.SerializerInterface, lcm: pydrake.lcm.DrakeLcmInterface, publish_period: float = 0.0, publish_offset: float = 0.0) -> None

A constructor for an LcmPublisherSystem that takes LCM message objects on its sole abstract-valued input port. The LCM message type is determined by the provided serializer. Will publish on forced events and either periodic or per-step events, as determined by publish_period.

Parameter channel:

The LCM channel on which to publish.

Parameter serializer:

The serializer that converts between byte vectors and LCM message objects. Cannot be null.

Parameter lcm:

A pointer to the LCM subsystem to use, which must remain valid for the lifetime of this object. If null, a drake::lcm::DrakeLcm object is allocated and maintained internally, but see the note in the class comments.

Parameter publish_period:

Period that messages will be published (optional). If the publish period is zero, LcmPublisherSystem will use per-step publishing instead; see LeafSystem::DeclarePerStepPublishEvent().

Parameter publish_offset:

Offset that messages will be published (optional), in seconds. This adds a phase-shift delay to periodic publish events.

Precondition:

publish_period is non-negative.

Precondition:

publish_offset is finite and non-negative.

Precondition:

publish_offset is set to zero when the publish_period is zero.

  1. __init__(self: pydrake.systems.lcm.LcmPublisherSystem, channel: str, serializer: pydrake.systems.lcm.SerializerInterface, lcm: pydrake.systems.lcm.LcmInterfaceSystem, publish_triggers: set[pydrake.systems.framework.TriggerType], publish_period: float = 0.0, publish_offset: float = 0.0) -> None

A constructor for an LcmPublisherSystem that takes LCM message objects on its sole abstract-valued input port. The LCM message type is determined by the provided serializer.

Parameter channel:

The LCM channel on which to publish.

Parameter serializer:

The serializer that converts between byte vectors and LCM message objects. Cannot be null.

Parameter lcm:

A pointer to the LCM subsystem to use, which must remain valid for the lifetime of this object. If null, a drake::lcm::DrakeLcm object is allocated and maintained internally, but see the note in the class comments.

Parameter publish_triggers:

Set of triggers that determine when messages will be published. Supported TriggerTypes are {kForced, kPeriodic, kPerStep}. Will throw an exception if empty or if unsupported types are provided.

Parameter publish_period:

Period that messages will be published (optional). publish_period should only be non-zero if one of the publish_triggers is kPerStep.

Parameter publish_offset:

Offset that messages will be published (optional), in seconds. This adds a phase-shift delay to periodic publish events.

Precondition:

publish_triggers contains a subset of {kForced, kPeriodic, kPerStep}.

Precondition:

publish_period is non-negative.

Precondition:

publish_period > 0 if and only if publish_triggers contains kPeriodic.

Precondition:

publish_offset is finite and non-negative.

Precondition:

publish_offset > 0 if and only if publish_triggers contains kPeriodic.

  1. __init__(self: pydrake.systems.lcm.LcmPublisherSystem, channel: str, serializer: pydrake.systems.lcm.SerializerInterface, lcm: pydrake.lcm.DrakeLcmInterface, publish_triggers: set[pydrake.systems.framework.TriggerType], publish_period: float = 0.0, publish_offset: float = 0.0) -> None

A constructor for an LcmPublisherSystem that takes LCM message objects on its sole abstract-valued input port. The LCM message type is determined by the provided serializer.

Parameter channel:

The LCM channel on which to publish.

Parameter serializer:

The serializer that converts between byte vectors and LCM message objects. Cannot be null.

Parameter lcm:

A pointer to the LCM subsystem to use, which must remain valid for the lifetime of this object. If null, a drake::lcm::DrakeLcm object is allocated and maintained internally, but see the note in the class comments.

Parameter publish_triggers:

Set of triggers that determine when messages will be published. Supported TriggerTypes are {kForced, kPeriodic, kPerStep}. Will throw an exception if empty or if unsupported types are provided.

Parameter publish_period:

Period that messages will be published (optional). publish_period should only be non-zero if one of the publish_triggers is kPerStep.

Parameter publish_offset:

Offset that messages will be published (optional), in seconds. This adds a phase-shift delay to periodic publish events.

Precondition:

publish_triggers contains a subset of {kForced, kPeriodic, kPerStep}.

Precondition:

publish_period is non-negative.

Precondition:

publish_period > 0 if and only if publish_triggers contains kPeriodic.

Precondition:

publish_offset is finite and non-negative.

Precondition:

publish_offset > 0 if and only if publish_triggers contains kPeriodic.

static Make(channel, lcm_type, lcm, publish_period=0.0, use_cpp_serializer=False, *, publish_triggers=None, publish_offset=0.0)

Convenience to create an LCM publisher system with a concrete type.

Parameters
  • channel – LCM channel name.

  • lcm_type – Python class generated by lcmgen.

  • lcm – LCM service instance.

  • publish_period – System’s publish period (in seconds). Default is 0.

  • publish_offset – System’s publish offset (in seconds). Default is 0.

  • use_cpp_serializer – Use C++ serializer to interface with LCM converter systems that are implemented in C++. LCM types must be registered in C++ via BindCppSerializer.

class pydrake.systems.lcm.LcmScopeSystem

Bases: pydrake.systems.framework.LeafSystem

__init__(self: pydrake.systems.lcm.LcmScopeSystem, size: int) None

(Advanced.) Most users will use AddToBuilder instead of this constructor. On its own, this constructor does not publish anything.

Creates a system with one input port and one output port. The input accepts a vector of the given size. The output produces an lcmt_scope message.

static AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, lcm: pydrake.lcm.DrakeLcmInterface, signal: pydrake.systems.framework.OutputPort, channel: str, publish_period: float) list

Adds an LcmScopeSystem and LcmPublisherSystem to the given builder.

Parameter lcm:

A pointer to the LCM subsystem to use, which must remain valid for the lifetime of builder. This will typically be an instance of an LcmInterfaceSystem that’s already been added to the builder.

Parameter signal:

The output port to be scoped. Must be an OutputPort of a system that’s already been added to the builder.

Parameter channel:

The LCM channel on which to publish.

Parameter publish_period:

Specifies how often messages will be published. If the period is zero, the LcmPublisherSystem will publish every step.

class pydrake.systems.lcm.LcmSubscriberSystem

Bases: pydrake.systems.framework.LeafSystem

__init__(*args, **kwargs)

Overloaded function.

  1. __init__(self: pydrake.systems.lcm.LcmSubscriberSystem, channel: str, serializer: pydrake.systems.lcm.SerializerInterface, lcm: pydrake.systems.lcm.LcmInterfaceSystem, wait_for_message_on_initialization_timeout: float = 0.0) -> None

Constructor that returns a subscriber System that provides message objects on its sole abstract-valued output port. The type of the message object is determined by the serializer.

Parameter channel:

The LCM channel on which to subscribe.

Parameter serializer:

The serializer that converts between byte vectors and LCM message objects. Cannot be null.

Parameter lcm:

A non-null pointer to the LCM subsystem to subscribe on. If wait_for_message_on_initialization_timeout > 0, then the pointer must remain valid for the lifetime of the returned system.

Parameter wait_for_message_on_initialization_timeout:

Configures the behavior of initialization events (see System::ExecuteInitializationEvents() and Simulator::Initialize()) by specifying the number of seconds (wall-clock elapsed time) to wait for a new message. If this timeout is <= 0, initialization will copy any already-received messages into the Context but will not process any new messages. If this timeout is > 0, initialization will call lcm->HandleSubscriptions() until at least one message is received or until the timeout. Pass ∞ to wait indefinitely.

  1. __init__(self: pydrake.systems.lcm.LcmSubscriberSystem, channel: str, serializer: pydrake.systems.lcm.SerializerInterface, lcm: pydrake.lcm.DrakeLcmInterface, wait_for_message_on_initialization_timeout: float = 0.0) -> None

Constructor that returns a subscriber System that provides message objects on its sole abstract-valued output port. The type of the message object is determined by the serializer.

Parameter channel:

The LCM channel on which to subscribe.

Parameter serializer:

The serializer that converts between byte vectors and LCM message objects. Cannot be null.

Parameter lcm:

A non-null pointer to the LCM subsystem to subscribe on. If wait_for_message_on_initialization_timeout > 0, then the pointer must remain valid for the lifetime of the returned system.

Parameter wait_for_message_on_initialization_timeout:

Configures the behavior of initialization events (see System::ExecuteInitializationEvents() and Simulator::Initialize()) by specifying the number of seconds (wall-clock elapsed time) to wait for a new message. If this timeout is <= 0, initialization will copy any already-received messages into the Context but will not process any new messages. If this timeout is > 0, initialization will call lcm->HandleSubscriptions() until at least one message is received or until the timeout. Pass ∞ to wait indefinitely.

static Make(channel, lcm_type, lcm, use_cpp_serializer=False, *, wait_for_message_on_initialization_timeout=0.0)

Convenience to create an LCM subscriber system with a concrete type.

Parameters
  • channel – LCM channel name.

  • lcm_type – Python class generated by lcmgen.

  • lcm – LCM service instance.

  • use_cpp_serializer – Use C++ serializer to interface with LCM converter systems that are implemented in C++. LCM types must be registered in C++ via BindCppSerializer.

  • wait_for_message_on_initialization_timeout – Configures the behavior of initialization events (see System.ExecuteInitializationEvents and Simulator.Initialize) by specifying the number of seconds (wall-clock elapsed time) to wait for a new message. If this timeout is <= 0, initialization will copy any already-received messages into the Context but will not process any new messages. If this timeout is > 0, initialization will call lcm.HandleSubscriptions() until at least one message is received or until the timeout. Pass ∞ to wait indefinitely.

WaitForMessage(self: pydrake.systems.lcm.LcmSubscriberSystem, old_message_count: int, message: pydrake.common.value.AbstractValue = None, timeout: float = - 1) int

Blocks the caller until its internal message count exceeds old_message_count with an optional timeout.

Parameter old_message_count:

Internal message counter.

Parameter message:

If non-null, will return the received message.

Parameter timeout:

The duration (in seconds) to wait before returning; a non-positive duration will not time out.

Returns

Returns the new count of received messages. If a timeout occurred, this will be less than or equal to old_message_count.

Precondition:

If message is specified, this system must be abstract-valued.

class pydrake.systems.lcm.PySerializer(lcm_type)

Bases: pydrake.systems.lcm.SerializerInterface

Provides a Python implementation of SerializerInterface for use with LcmPublisherSystem and LcmSubscriberSystem when the given lcm_type is a Python object (not a C++ object).

__init__(self: pydrake.systems.lcm.SerializerInterface) None
CreateDefaultValue(self: pydrake.systems.lcm.SerializerInterface) pydrake.common.value.AbstractValue

Creates a value-initialized (zeroed) instance of the message object. The result can be used as the output object filled in by Deserialize.

Deserialize(self: pydrake.systems.lcm.SerializerInterface, message_bytes: bytes, abstract_value: pydrake.common.value.AbstractValue) None

Translates LCM message bytes into a drake::AbstractValue object.

Serialize(self: pydrake.systems.lcm.SerializerInterface, abstract_value: pydrake.common.value.AbstractValue) bytes

Translates a drake::AbstractValue object into LCM message bytes.

class pydrake.systems.lcm.SerializerInterface
__init__(self: pydrake.systems.lcm.SerializerInterface) None
CreateDefaultValue(self: pydrake.systems.lcm.SerializerInterface) pydrake.common.value.AbstractValue

Creates a value-initialized (zeroed) instance of the message object. The result can be used as the output object filled in by Deserialize.

Deserialize(self: pydrake.systems.lcm.SerializerInterface, message_bytes: bytes, abstract_value: pydrake.common.value.AbstractValue) None

Translates LCM message bytes into a drake::AbstractValue object.

Serialize(self: pydrake.systems.lcm.SerializerInterface, abstract_value: pydrake.common.value.AbstractValue) bytes

Translates a drake::AbstractValue object into LCM message bytes.