pydrake.multibody.meshcat

Interface code for Meshcat-based visualization

class pydrake.multibody.meshcat.ContactVisualizer

Bases: pydrake.systems.framework.LeafSystem

ContactVisualizer is a system that publishes a ContactResults to geometry::Meshcat; For point contact results, it draws double-sided arrows at the location of the contact force with length scaled by the magnitude of the contact force. For hydroelastic contact, it draws single-sided arrows at the centroid of the contact patch, one for force and one for the moment of the contact results. The length of these vectors are scaled by the magnitude of the contact force/moment. The direction of the arrow is essentially arbitrary (based on the GeometryIds) but is stable during a simulation. The most common use of this system is to connect its input port to the contact results output port of a MultibodyPlant.

contact_results→
query_object (optional)→
ContactVisualizer

Warning

In the current implementation, ContactVisualizer methods must be called from the same thread where the class instance was constructed. For example, running multiple simulations in parallel using the same ContactVisualizer instance is not yet supported. We may generalize this in the future.

Note

This class is templated; see ContactVisualizer_ for the list of instantiations.

__init__(self: pydrake.multibody.meshcat.ContactVisualizer, meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix='contact_forces', delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) None

Creates an instance of ContactVisualizer

static AddToBuilder(*args, **kwargs)

Overloaded function.

  1. AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, plant: pydrake.multibody.plant.MultibodyPlant, meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix=’contact_forces’, delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) -> pydrake.multibody.meshcat.ContactVisualizer

Adds a ContactVisualizer and connects it to the given MultibodyPlant’s multibody::ContactResults-valued output port and geometry::QueryObject-valued output port. The ContactVisualizer’s name (see systems::SystemBase::set_name) will be set to a sensible default value, unless the default name was already in use by another system.

  1. AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, contact_results_port: pydrake.systems.framework.OutputPort, query_object_port: pydrake.systems.framework.OutputPort, meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix=’contact_forces’, delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) -> pydrake.multibody.meshcat.ContactVisualizer

Adds a ContactVisualizer and connects it to the given multibody::ContactResults-valued output port and the given geometry::QueryObject-valued output port. The ContactVisualizer’s name (see systems::SystemBase::set_name) will be set to a sensible default value, unless the default name was already in use by another system.

  1. AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder, contact_results_port: pydrake.systems.framework.OutputPort, meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix=’contact_forces’, delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) -> pydrake.multibody.meshcat.ContactVisualizer

Adds a ContactVisualizer and connects it to the given multibody::ContactResults-valued output port. The ContactVisualizer’s name (see systems::SystemBase::set_name) will be set to a sensible default value, unless the default name was already in use by another system.

Warning

This overload is dispreferred because it cannot show any geometry names in the visualizer.

contact_results_input_port(self: pydrake.multibody.meshcat.ContactVisualizer) pydrake.systems.framework.InputPort

Returns the multibody::ContactResults-valued input port. It should be connected to MultibodyPlant’s multibody::ContactResults-valued output port. Failure to do so will cause a runtime error when attempting to broadcast messages.

Delete(self: pydrake.multibody.meshcat.ContactVisualizer) None

Calls geometry::Meshcat::Delete(std::string_view path), with the path set to prefix. Since this visualizer will only ever add geometry under this prefix, this will remove all geometry/transforms added by the visualizer, or by a previous instance of this visualizer using the same prefix. Use the delete_on_initialization_event in the parameters to determine whether this should be called on initialization.

query_object_input_port(self: pydrake.multibody.meshcat.ContactVisualizer) pydrake.systems.framework.InputPort

Returns the geometry::QueryObject-valued input port. It should be (optionally) connected to SceneGraph’s get_query_output_port(). Failure to do so will prevent the display from showing names for the geometry.

template pydrake.multibody.meshcat.ContactVisualizer_

Instantiations: ContactVisualizer_[float], ContactVisualizer_[AutoDiffXd]

class pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]

Bases: pydrake.systems.framework.LeafSystem_[AutoDiffXd]

ContactVisualizer is a system that publishes a ContactResults to geometry::Meshcat; For point contact results, it draws double-sided arrows at the location of the contact force with length scaled by the magnitude of the contact force. For hydroelastic contact, it draws single-sided arrows at the centroid of the contact patch, one for force and one for the moment of the contact results. The length of these vectors are scaled by the magnitude of the contact force/moment. The direction of the arrow is essentially arbitrary (based on the GeometryIds) but is stable during a simulation. The most common use of this system is to connect its input port to the contact results output port of a MultibodyPlant.

contact_results→
query_object (optional)→
ContactVisualizer

Warning

In the current implementation, ContactVisualizer methods must be called from the same thread where the class instance was constructed. For example, running multiple simulations in parallel using the same ContactVisualizer instance is not yet supported. We may generalize this in the future.

__init__(self: pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd], meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix='contact_forces', delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) None

Creates an instance of ContactVisualizer

static AddToBuilder(*args, **kwargs)

Overloaded function.

  1. AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder_[AutoDiffXd], plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix=’contact_forces’, delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) -> pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]

Adds a ContactVisualizer and connects it to the given MultibodyPlant’s multibody::ContactResults-valued output port and geometry::QueryObject-valued output port. The ContactVisualizer’s name (see systems::SystemBase::set_name) will be set to a sensible default value, unless the default name was already in use by another system.

  1. AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder_[AutoDiffXd], contact_results_port: pydrake.systems.framework.OutputPort_[AutoDiffXd], query_object_port: pydrake.systems.framework.OutputPort_[AutoDiffXd], meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix=’contact_forces’, delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) -> pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]

Adds a ContactVisualizer and connects it to the given multibody::ContactResults-valued output port and the given geometry::QueryObject-valued output port. The ContactVisualizer’s name (see systems::SystemBase::set_name) will be set to a sensible default value, unless the default name was already in use by another system.

  1. AddToBuilder(builder: pydrake.systems.framework.DiagramBuilder_[AutoDiffXd], contact_results_port: pydrake.systems.framework.OutputPort_[AutoDiffXd], meshcat: pydrake.geometry.Meshcat, params: pydrake.multibody.meshcat.ContactVisualizerParams = ContactVisualizerParams(publish_period=0.03125, color=Rgba(r=0.0, g=1.0, b=0.0, a=1.0), hydro_force_color=Rgba(r=1.0, g=0.0, b=0.0, a=1.0), hydro_moment_color=Rgba(r=0.0, g=0.0, b=1.0, a=1.0), prefix=’contact_forces’, delete_on_initialization_event=True, force_threshold=0.01, moment_threshold=0.01, newtons_per_meter=10.0, newton_meters_per_meter=3.0, radius=0.002)) -> pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]

Adds a ContactVisualizer and connects it to the given multibody::ContactResults-valued output port. The ContactVisualizer’s name (see systems::SystemBase::set_name) will be set to a sensible default value, unless the default name was already in use by another system.

Warning

This overload is dispreferred because it cannot show any geometry names in the visualizer.

contact_results_input_port(self: pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]

Returns the multibody::ContactResults-valued input port. It should be connected to MultibodyPlant’s multibody::ContactResults-valued output port. Failure to do so will cause a runtime error when attempting to broadcast messages.

Delete(self: pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]) None

Calls geometry::Meshcat::Delete(std::string_view path), with the path set to prefix. Since this visualizer will only ever add geometry under this prefix, this will remove all geometry/transforms added by the visualizer, or by a previous instance of this visualizer using the same prefix. Use the delete_on_initialization_event in the parameters to determine whether this should be called on initialization.

query_object_input_port(self: pydrake.multibody.meshcat.ContactVisualizer_[AutoDiffXd]) pydrake.systems.framework.InputPort_[AutoDiffXd]

Returns the geometry::QueryObject-valued input port. It should be (optionally) connected to SceneGraph’s get_query_output_port(). Failure to do so will prevent the display from showing names for the geometry.

class pydrake.multibody.meshcat.ContactVisualizerParams

The set of parameters for configuring ContactVisualizer.

__init__(self: pydrake.multibody.meshcat.ContactVisualizerParams, **kwargs) None
property color

The color used to draw the point contact force arrows.

property delete_on_initialization_event

Determines whether to send a Meshcat::Delete(prefix) message on an initialization event to remove any visualizations e.g. from a previous simulation. See declare_initialization_events “Declare initialization events” for more information.

property force_threshold

The threshold (in N) below which forces will no longer be drawn. The ContactVisualizer constructor enforces that this must be strictly positive; zero forces do not have a meaningful direction and cannot be visualized.

property hydro_force_color

The color used to draw the hydroelastic contact force arrows.

property hydro_moment_color

The color used to draw the hydroelastic contact moment arrows.

property moment_threshold

The threshold (in N⋅m) below which moments will no longer be drawn. The ContactVisualizer constructor enforces that this must be strictly positive; zero moments do not have a meaningful direction and cannot be visualized.

property newton_meters_per_meter

Sets the length scale of the moment vectors.

property newtons_per_meter

Sets the length scale of the force vectors.

property prefix

A prefix to add to the path for all objects and transforms curated by the ContactVisualizer. It can be an absolute path or relative path. If relative, this prefix will be appended to the geometry::Meshcat prefix based on the standard path semantics in Meshcat. See meshcat_path “Meshcat paths” for details.

property publish_period

The duration (in simulation seconds) between attempts to update poses in the visualizer. (To help avoid small simulation time steps, we use a default period that has an exact representation in binary floating point; see drake#15021 for details.)

property radius

The radius of cylinder geometry used in the force/moment vector.

class pydrake.multibody.meshcat.JointSliders

Bases: pydrake.systems.framework.LeafSystem

JointSliders adds slider bars to the Meshcat control panel for the joints of a MultibodyPlant. These might be useful for interactive or teleoperation demos. The sliders’ current values are available on the positions output port of this system.

JointSliders
→ positions

The output port is of size plant.num_positions(), and the order of its elements matches plant.GetPositions().

Only positions associated with joints get sliders. All other positions are fixed at nominal values.

Beware that the output port of this system always provides the sliders’ current values, even if evaluated by multiple different downstream input ports during a single computation. If you need to have a synchronized view of the slider data, place a systems::ZeroOrderHold system between the sliders and downstream calculations.

Note

This class is templated; see JointSliders_ for the list of instantiations.

__init__(self: pydrake.multibody.meshcat.JointSliders, meshcat: pydrake.geometry.Meshcat, plant: pydrake.multibody.plant.MultibodyPlant, initial_value: Optional[numpy.ndarray[numpy.float64[m, 1]]] = None, lower_limit: Union[None, float, numpy.ndarray[numpy.float64[m, 1]]] = None, upper_limit: Union[None, float, numpy.ndarray[numpy.float64[m, 1]]] = None, step: Union[None, float, numpy.ndarray[numpy.float64[m, 1]]] = None, decrement_keycodes: List[str] = [], increment_keycodes: List[str] = []) None

Creates a meshcat slider for each joint in the given plant.

Parameter meshcat:

The Meshcat instance where the sliders will be added.

Parameter plant:

The MultibodyPlant to create sliders for. The plant pointer is aliased for the lifetime of this JointSliders object.

Parameter initial_value:

(Optional) If provided, the sliders’ initial values will be as given; otherwise, the plant’s default values will be used.

Parameter lower_limit:

(Optional) The lower limit of the slider will be the maximum value of this number and any limit specified in the Joint. May be a single value or else a vector of length plant.num_positions(). If no value is provided, a sensible default will be used.

Parameter upper_limit:

(Optional) The upper limit of the slider will be the minimum value of this number and any limit specified in the Joint. May be a single value or else a vector of length plant.num_positions(). If no value is provided, a sensible default will be used.

Parameter step:

(Optional) The step argument of the slider, which is the smallest increment by which the slider can change values (and therefore update our output port’s value). May be a single value or else a vector of length plant.num_positions(). If no value is provided, a sensible default will be used.

Parameter decrement_keycodes:

(Optional) A vector of length plant.num_positions() with keycodes to assign to decrement the value of each individual joint slider. See Meshcat::AddSlider for more details.

Parameter increment_keycodes:

(Optional) A vector of length plant.num_positions() with keycodes to assign to increment the value of each individual joint slider. See Meshcat::AddSlider for more details.

Delete(self: pydrake.multibody.meshcat.JointSliders) None

Removes our sliders from the associated meshcat instance.

From this point on, our output port produces the initial_value from the constructor, not any slider values.

Warning

It is not safe to call this when a CalcOutput might be happening on this instance concurrently on another thread.

Run(self: pydrake.multibody.meshcat.JointSliders, diagram: pydrake.systems.framework.Diagram, timeout: Optional[float] = None, stop_button_keycode: str = 'Escape') numpy.ndarray[numpy.float64[m, 1]]

Publishes the given Diagram (typically, to cause it to be visualized) whenever our sliders’ values change. Blocks until the user clicks a “Stop” button in the MeshCat control panel, or if the timeout limit is reached.

Parameter timeout:

(Optional) In the absence of a button click, the duration (in seconds) to wait before returning. If the button is clicked, this function will return promptly, without waiting for the timeout. When no timeout is given, this function will block indefinitely.

Parameter stop_button_keycode:

a keycode that will be assigned to the “Stop” button. Setting this to the empty string means no keycode. See Meshcat::AddButton for details. $*Default:* “Escape”.

Returns

the output of plant.GetPositions() given the most recently published value of the plant Context.

Precondition:

diagram must be a top-level (i.e., “root”) diagram.

Precondition:

diagram must contain the plant that was passed into this JointSliders system’s constructor.

Precondition:

diagram must contain this JointSliders system, however the output of these sliders need not be connected (even indirectly) to any plant input port. The positions of the plant will be updated directly using a call to plant.SetPositions(...) when the slider values change.

SetPositions(self: pydrake.multibody.meshcat.JointSliders, q: numpy.ndarray[numpy.float64[m, 1]]) None

Sets all robot positions (corresponding to joint positions and potentially positions not associated with any joint) to the values in q. The meshcat sliders associated with any joint positions described by q will have their value updated. Additionally, the “initial state” vector of positions tracked by this instance will be updated to the values in q. This “initial state” vector update will persist even if sliders are removed (e.g., via Delete).

Parameter q:

A vector whose length is equal to the associated MultibodyPlant::num_positions().

template pydrake.multibody.meshcat.JointSliders_

Instantiations: JointSliders_[float], JointSliders_[AutoDiffXd]

class pydrake.multibody.meshcat.JointSliders_[AutoDiffXd]

Bases: pydrake.systems.framework.LeafSystem_[AutoDiffXd]

JointSliders adds slider bars to the Meshcat control panel for the joints of a MultibodyPlant. These might be useful for interactive or teleoperation demos. The sliders’ current values are available on the positions output port of this system.

JointSliders
→ positions

The output port is of size plant.num_positions(), and the order of its elements matches plant.GetPositions().

Only positions associated with joints get sliders. All other positions are fixed at nominal values.

Beware that the output port of this system always provides the sliders’ current values, even if evaluated by multiple different downstream input ports during a single computation. If you need to have a synchronized view of the slider data, place a systems::ZeroOrderHold system between the sliders and downstream calculations.

__init__(self: pydrake.multibody.meshcat.JointSliders_[AutoDiffXd], meshcat: pydrake.geometry.Meshcat, plant: pydrake.multibody.plant.MultibodyPlant_[AutoDiffXd], initial_value: Optional[numpy.ndarray[numpy.float64[m, 1]]] = None, lower_limit: Union[None, float, numpy.ndarray[numpy.float64[m, 1]]] = None, upper_limit: Union[None, float, numpy.ndarray[numpy.float64[m, 1]]] = None, step: Union[None, float, numpy.ndarray[numpy.float64[m, 1]]] = None, decrement_keycodes: List[str] = [], increment_keycodes: List[str] = []) None

Creates a meshcat slider for each joint in the given plant.

Parameter meshcat:

The Meshcat instance where the sliders will be added.

Parameter plant:

The MultibodyPlant to create sliders for. The plant pointer is aliased for the lifetime of this JointSliders object.

Parameter initial_value:

(Optional) If provided, the sliders’ initial values will be as given; otherwise, the plant’s default values will be used.

Parameter lower_limit:

(Optional) The lower limit of the slider will be the maximum value of this number and any limit specified in the Joint. May be a single value or else a vector of length plant.num_positions(). If no value is provided, a sensible default will be used.

Parameter upper_limit:

(Optional) The upper limit of the slider will be the minimum value of this number and any limit specified in the Joint. May be a single value or else a vector of length plant.num_positions(). If no value is provided, a sensible default will be used.

Parameter step:

(Optional) The step argument of the slider, which is the smallest increment by which the slider can change values (and therefore update our output port’s value). May be a single value or else a vector of length plant.num_positions(). If no value is provided, a sensible default will be used.

Parameter decrement_keycodes:

(Optional) A vector of length plant.num_positions() with keycodes to assign to decrement the value of each individual joint slider. See Meshcat::AddSlider for more details.

Parameter increment_keycodes:

(Optional) A vector of length plant.num_positions() with keycodes to assign to increment the value of each individual joint slider. See Meshcat::AddSlider for more details.

Delete(self: pydrake.multibody.meshcat.JointSliders_[AutoDiffXd]) None

Removes our sliders from the associated meshcat instance.

From this point on, our output port produces the initial_value from the constructor, not any slider values.

Warning

It is not safe to call this when a CalcOutput might be happening on this instance concurrently on another thread.

Run(self: pydrake.multibody.meshcat.JointSliders_[AutoDiffXd], diagram: pydrake.systems.framework.Diagram_[AutoDiffXd], timeout: Optional[float] = None, stop_button_keycode: str = 'Escape') numpy.ndarray[numpy.float64[m, 1]]

Publishes the given Diagram (typically, to cause it to be visualized) whenever our sliders’ values change. Blocks until the user clicks a “Stop” button in the MeshCat control panel, or if the timeout limit is reached.

Parameter timeout:

(Optional) In the absence of a button click, the duration (in seconds) to wait before returning. If the button is clicked, this function will return promptly, without waiting for the timeout. When no timeout is given, this function will block indefinitely.

Parameter stop_button_keycode:

a keycode that will be assigned to the “Stop” button. Setting this to the empty string means no keycode. See Meshcat::AddButton for details. $*Default:* “Escape”.

Returns

the output of plant.GetPositions() given the most recently published value of the plant Context.

Precondition:

diagram must be a top-level (i.e., “root”) diagram.

Precondition:

diagram must contain the plant that was passed into this JointSliders system’s constructor.

Precondition:

diagram must contain this JointSliders system, however the output of these sliders need not be connected (even indirectly) to any plant input port. The positions of the plant will be updated directly using a call to plant.SetPositions(...) when the slider values change.

SetPositions(self: pydrake.multibody.meshcat.JointSliders_[AutoDiffXd], q: numpy.ndarray[numpy.float64[m, 1]]) None

Sets all robot positions (corresponding to joint positions and potentially positions not associated with any joint) to the values in q. The meshcat sliders associated with any joint positions described by q will have their value updated. Additionally, the “initial state” vector of positions tracked by this instance will be updated to the values in q. This “initial state” vector update will persist even if sliders are removed (e.g., via Delete).

Parameter q:

A vector whose length is equal to the associated MultibodyPlant::num_positions().