pydrake.visualization

Bindings for Visualization.

pydrake.visualization.AddDefaultVisualization(builder: pydrake.systems.framework.DiagramBuilder, meshcat: pydrake.geometry.Meshcat = None) None

Adds LCM visualization publishers to communicate to Meshcat and/or Meldis, using all of the default configuration settings.

Parameter meshcat:

An optional existing Meshcat instance. (If nullptr, then a meshcat instance will be created.)

Example

Click to expand C++ code...
// Create a builder.
DiagramBuilder<double> builder;

// Add the MultibodyPlant and SceneGraph.
const MultibodyPlantConfig plant_config = ...;
MultibodyPlant<double>& plant = AddMultibodyPlant(plant_config, &builder);
// ... populate the plant, e.g., with a Parser, ...
plant.Finalize();

// Add the visualization.
AddDefaultVisualization(&builder);

// Simulate.
Simulator<double> simulator(builder.Build());
// ... etc ...
Precondition:

AddMultibodyPlant() or AddMultibodyPlantSceneGraph() has already been called on the given builder.

Precondition:

The MultibodyPlant in the given builder is already finalized, as in plant.Finalize().

See also

drake::visualization::ApplyVisualizationConfig()

See also

drake::multibody::AddMultibodyPlant()

pydrake.visualization.AddFrameTriadIllustration(*, scene_graph: pydrake.geometry.SceneGraph, body: Optional[pydrake.multibody.tree.RigidBody] = None, frame: Optional[pydrake.multibody.tree.Frame] = None, frame_index: Optional[pydrake.multibody.tree.FrameIndex] = None, frame_id: Optional[pydrake.geometry.FrameId] = None, plant: Optional[pydrake.multibody.plant.MultibodyPlant] = None, name: Optional[str] = None, length: float = 0.3, radius: float = 0.005, opacity: float = 0.9, X_FT: Optional[pydrake.math.RigidTransform] = None)

Adds illustration geometry representing the given frame using an RGB triad, with the x-axis drawn in red, the y-axis in green and the z-axis in blue. The given frame can be either a geometry FrameId, a multibody RigidBody, a multibody FrameIndex or a multibody Frame.

Note: exactly one of body=, frame=, frame_index= or frame_id= must be provided.

Note: body frames and frames fixed to bodies are colored differently (body frames are brighter).

Parameters
  • scene_graph – the SceneGraph where geometry will be added.

  • body – when provided, illustrates the frame of the given body.

  • frame – when provided, illustrates the frame from a plant.

  • frame_index – when provided, illustrates the indexed frame from a plant. plant must not be None.

  • frame_id – when provided, illustrates the given geometry.FrameId registered with the given plant and scene_graph.

  • plant – MultibodyPlant associated with the given frame_id; required if frame_index= or frame_id= is being used. If body= or frame= is supplied, they must belong to this plant.

  • name – the added geometries will have names “_frames::{name}::x-axis”, etc. If None, the name is inferred from the indicated frame.

  • length – the length of each axis in meters.

  • radius – the radius of each axis in meters.

  • opacity – the opacity each axis, between 0.0 and 1.0.

  • X_FT – optional rigid transform relating frame T (the triad geometry) and frame F (the given body=, frame=, or frame_id= frame); when None, X_FT is the identity transform and therefore the triad will depict F.

Returns

The newly-added geometry ids for (x, y, z) respectively.

pydrake.visualization.ApplyVisualizationConfig(config: pydrake.visualization.VisualizationConfig, builder: pydrake.systems.framework.DiagramBuilder, lcm_buses: pydrake.systems.lcm.LcmBuses = None, plant: pydrake.multibody.plant.MultibodyPlant = None, scene_graph: pydrake.geometry.SceneGraph = None, meshcat: pydrake.geometry.Meshcat = None, lcm: pydrake.lcm.DrakeLcmInterface = None) None

Adds LCM visualization publishers to communicate to Meshcat and/or Meldis.

Example

Click to expand C++ code...
// Create a builder.
DiagramBuilder<double> builder;

// Add the MultibodyPlant and SceneGraph.
const MultibodyPlantConfig plant_config = ...;
MultibodyPlant<double>& plant = AddMultibodyPlant(plant_config, &builder);
// ... populate the plant, e.g., with a Parser, ...
plant.Finalize();

// Add the visualization.
const VisualizationConfig vis_config = ...;
ApplyVisualizationConfig(vis_config, &builder);

// Simulate.
Simulator<double> simulator(builder.Build());
// ... etc ...
Parameter config:

The visualization configuration.

Parameter builder:

The diagram to add visualization systems into.

Parameter lcm_buses:

(Optional) The available LCM buses to use for visualization message publication. When not provided, uses the lcm interface if provided, or else the config.lcm_bus must be set to “default” in which case an appropriate drake::lcm::DrakeLcm object is constructed and used internally.

Parameter plant:

(Optional) The MultibodyPlant to visualize. In the common case where a MultibodyPlant has already been added to builder using either AddMultibodyPlant() or AddMultibodyPlantSceneGraph(), the default value (nullptr) here is suitable and generally should be preferred. When provided, it must be a System that’s been added to the the given builder. When not provided, visualizes the system named “plant” in the given builder.

Parameter scene_graph:

(Optional) The SceneGraph to visualize. In the common case where a SceneGraph has already been added to builder using either AddMultibodyPlant() or AddMultibodyPlantSceneGraph(), the default value (nullptr) here is suitable and generally should be preferred. When provided, it must be a System that’s been added to the the given builder. When not provided, visualizes the system named “scene_graph” in the given builder.

Parameter meshcat:

(Optional) A Meshcat object for visualization message publication. When not provided, a Meshcat object will be created unless config.enable_meshcat_creation is set to false.

Parameter lcm:

(Optional) The LCM interface used for visualization message publication. When not provided, uses the config.lcm_bus value to look up the appropriate interface from lcm_buses.

Precondition:

The builder is non-null.

Precondition:

Either the config.lcm_bus is set to “default”, or else lcm_buses is non-null and contains a bus named config.lcm_bus, or else lcm is non-null.

Precondition:

Either the given builder contains a MultibodyPlant system named “plant” or else the provided plant is non-null.

Precondition:

Either the given builder contains a SceneGraph system named “scene_graph” or else the provided scene_graph is non-null.

Precondition:

The MultibodyPlant is already finalized, as in plant.Finalize().

See also

drake::visualization::AddDefaultVisualization()

See also

drake::multibody::AddMultibodyPlant()

See also

drake::systems::lcm::ApplyLcmBusConfig()

class pydrake.visualization.ColorizeDepthImage

Bases: pydrake.systems.framework.LeafSystem

ColorizeDepthImage converts a depth image, either 32F or 16U, to a color image. One input port, and only one, must be connected.

depth_image_32f→
depth_image_16u→
ColorizeDepthImage
→ color_image

Depth measurements are linearly mapped to a grayscale palette, with smaller (closer) values brighter and larger (further) values darker.

The dynamic range of each input image determines the scale. The pixel with the smallest depth will be fully white (#FFFFFFFF), and largest depth will be fully black (#000000FF). Note that alpha channel is still 100% in both cases.

Because the dynamic range is measured one input image a time, take note that a video recording of this System will not have consistent scaling across its entirety. The ability to set a fixed palette is future work.

For the special depth pixel values “too close” or “too far”, the color pixel will use the invalid_color property (by default, a dim red).

__init__(self: pydrake.visualization.ColorizeDepthImage) None

Creates a ColorizeDepthImage system.

Calc(*args, **kwargs)

Overloaded function.

  1. Calc(self: pydrake.visualization.ColorizeDepthImage, arg0: pydrake.systems.sensors.Image[PixelType.kDepth32F], arg1: pydrake.systems.sensors.Image[PixelType.kRgba8U]) -> None

Colorizes the input into output, without using any System port conections nor any Context.

  1. Calc(self: pydrake.visualization.ColorizeDepthImage, arg0: pydrake.systems.sensors.Image[PixelType.kDepth16U], arg1: pydrake.systems.sensors.Image[PixelType.kRgba8U]) -> None

Colorizes the input into output, without using any System port conections nor any Context.

property invalid_color

The color used for pixels with too-near or too-far depth.

class pydrake.visualization.ColorizeLabelImage

Bases: pydrake.systems.framework.LeafSystem

ColorizeLabelImage converts a label image to a color image.

label_image→
ColorizeLabelImage
→ color_image

Labels are mapped to colors with a built-in, fixed palette. The palette has fewer elements than all possible labels, so not all labels will necessarily be represented by a unique color. For label pixels that do not represent a label (“don’t care”, “empty”, “unspecified”, etc.), the color pixel will use the background_color property (by default, black with 0% alpha).

__init__(self: pydrake.visualization.ColorizeLabelImage) None

Creates a ColorizeLabelImage system.

property background_color

The color used for pixels with no label.

Calc(self: pydrake.visualization.ColorizeLabelImage, arg0: pydrake.systems.sensors.Image[PixelType.kLabel16I], arg1: pydrake.systems.sensors.Image[PixelType.kRgba8U]) None

Colorizes the input into output, without using any System port conections nor any Context.

class pydrake.visualization.ConcatenateImages

Bases: pydrake.systems.framework.LeafSystem

ConcatenateImages stacks multiple input images into a single output image.

color_image_r0_c0→
color_image_r0_c1→
...→
ConcatenateImages
→ color_image

All inputs must be of type ImageRgba8U.

Any input port may be disconnected, in which case it will be interpreted as zero-sized image.

In case of non-uniform image sizes, any gaps between images will be filled with all-zero pixels (i.e., with 0% alpha).

__init__(self: pydrake.visualization.ConcatenateImages, *, rows: int = 1, cols: int = 1) None

Constructs a ConcatenateImages system.

Parameter rows:

Number of images to stack vertically.

Parameter cols:

Number of images to stack horizontally.

get_input_port(self: pydrake.visualization.ConcatenateImages, *, row: int, col: int) pydrake.systems.framework.InputPort

Returns the InputPort for the given (row, col) image. Rows and columns are 0-indexed, i.e., we have 0 <= row < rows and 0 <= col < cols.

class pydrake.visualization.Meldis(*, meshcat_host: Optional[str] = None, meshcat_port: Optional[int] = None, meshcat_params: Optional[pydrake.geometry.MeshcatParams] = None, environment_map: Optional[pathlib.Path] = None)

Bases: object

MeshCat LCM Display Server (MeLDiS)

Offers a MeshCat visualization server that listens for and draws Drake’s legacy LCM visualization messages.

If the meshcat_host parameter is not supplied, ‘localhost’ will be used by default.

Refer to the pydrake.visualization.meldis module docs for details.

__init__(*, meshcat_host: Optional[str] = None, meshcat_port: Optional[int] = None, meshcat_params: Optional[pydrake.geometry.MeshcatParams] = None, environment_map: Optional[pathlib.Path] = None)

Constructs a new Meldis instance. The meshcat_host (when given) takes precedence over meshcat_params.host. The meshcat_post (when given) takes precedence over meshcat_params.port.

serve_forever(*, idle_timeout=None)

Runs indefinitely, forwarding LCM => MeshCat messages.

If provided, the optional idle_timeout must be strictly positive and this loop will sys.exit after that many seconds without any websocket connections.

class pydrake.visualization.MeshcatPoseSliders

Bases: pydrake.systems.framework.LeafSystem

MeshcatPoseSliders adds slider bars to the MeshCat control panel for the roll, pitch, yaw, x, y, z control of a pose. These might be useful for interactive or teleoperation demos. The abstract-value pose is available on the pose output port of this system.

pose (optional)→
MeshcatPoseSliders
→ pose

The optional pose input port is used ONLY at initialization; it can be used to set the pose during an Initialization event. If connected, it will take precedence over any initial_pose specified in the constructor.

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 MeshcatPoseSliders_ for the list of instantiations.

__init__()
__init__(self: pydrake.visualization.MeshcatPoseSliders, meshcat: pydrake.geometry.Meshcat, initial_pose: pydrake.math.RigidTransform = RigidTransform(
R=RotationMatrix([

[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0],

]), p=[0.0, 0.0, 0.0],

), lower_limit: numpy.ndarray[numpy.float64[6, 1]] = array([-3.14159265, -3.14159265, -3.14159265, -1. , -1. ,

-1. ]), upper_limit: numpy.ndarray[numpy.float64[6, 1]] = array([3.14159265, 3.14159265, 3.14159265, 1. , 1. , 1. ]), step: numpy.ndarray[numpy.float64[6, 1]] = array([0.01, 0.01, 0.01, 0.01, 0.01, 0.01]), decrement_keycodes: List[str] = [‘KeyQ’, ‘KeyS’, ‘KeyA’, ‘KeyJ’, ‘KeyK’, ‘KeyU’], increment_keycodes: List[str] = [‘KeyE’, ‘KeyW’, ‘KeyD’, ‘KeyL’, ‘KeyI’, ‘KeyO’], prefix: str = ‘’, visible: numpy.ndarray[bool[6, 1]] = array([ True, True, True, True, True, True])) -> None

Creates MeshCat sliders for a roll-pitch-yaw-x-y-z parameterization of a pose (aka RigidTransform).

Parameter meshcat:

The MeshCat instance where the sliders will be added.

Parameter initial_pose:

(Optional) If provided, the sliders’ initial values will be as given.

Parameter lower_limit:

(Optional) The lower limit of the sliders for roll, pitch, yaw, x, y, z.

Parameter upper_limit:

(Optional) The upper limit of the sliders for roll, pitch, yaw, x, y, z.

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 6.

Parameter decrement_keycodes:

(Optional) A vector of length 6 with keycodes to assign to decrement the value of each slider (roll, pitch, yaw, x, y, z). See Meshcat::AddSlider for more details.

Parameter increment_keycodes:

(Optional) A vector of length 6 with keycodes to assign to increment the value of each slider (roll, pitch, yaw, x, y, z). See Meshcat::AddSlider for more details.

Parameter prefix:

(Optional) By default, the sliders will be named “roll, pitch, yaw, x, y, z”. If prefix is non-empty, the the sliders will be named “{prefix}_roll, {prefix}_pitch”, etc.

Parameter visible:

(Optional) If provided, determines which of the sliders (roll, pitch, yaw, x, y, z) are visible in the Meshcat window. This can be useful, for instance, if one only wants to control the pose in 2D (and therefore only show the sliders for e.g. yaw, x, and y).

The default keycodes provide the following keyboard mapping:

Click to expand C++ code...
┌───────┬┬───────┬┬───────┐        ┌───────┬┬───────┬┬───────┐
│   Q   ││   W   ││   E   │        │   U   ││   I   ││   O   │
│ roll- ││ pitch+││ roll+ │        │   z-  ││   y+  ││   z+  │
├───────┼┼───────┼┼───────┤        ├───────┼┼───────┼┼───────┤
├───────┼┼───────┼┼───────┤        ├───────┼┼───────┼┼───────┤
│   A   ││   S   ││   D   │        │   J   ││   K   ││   L   │
│  yaw- ││ pitch-││  yaw+ │        │   x-  ││   y-  ││   x+  │
└───────┴┴───────┴┴───────┘        └───────┴┴───────┴┴───────┘
Delete(self: pydrake.visualization.MeshcatPoseSliders) 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.visualization.MeshcatPoseSliders, system: pydrake.systems.framework.System, context: pydrake.systems.framework.Context, timeout: Optional[float] = None, stop_button_keycode: str = 'Escape') pydrake.math.RigidTransform

Publishes the given systems::System (typically, a Diagram including visualizers, 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 context:

The systems::Context for the systems::Diagram.

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 most recently output pose.

Precondition:

system must be this MeshcatPoseSliders system or be a top-level (i.e., “root”) diagram that contains this MeshcatPoseSliders system.

SetPose(self: pydrake.visualization.MeshcatPoseSliders, pose: pydrake.math.RigidTransform) None

Sets the pose to X. The MeshCat sliders will have their value updated. Additionally, the “initial pose” tracked by this instance will be updated to X. This “initial pose” update will persist even if sliders are removed (e.g., via Delete).

template pydrake.visualization.MeshcatPoseSliders_

Instantiations: MeshcatPoseSliders_[float], MeshcatPoseSliders_[AutoDiffXd]

class pydrake.visualization.MeshcatPoseSliders_[AutoDiffXd]

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

MeshcatPoseSliders adds slider bars to the MeshCat control panel for the roll, pitch, yaw, x, y, z control of a pose. These might be useful for interactive or teleoperation demos. The abstract-value pose is available on the pose output port of this system.

pose (optional)→
MeshcatPoseSliders
→ pose

The optional pose input port is used ONLY at initialization; it can be used to set the pose during an Initialization event. If connected, it will take precedence over any initial_pose specified in the constructor.

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__()
__init__(self: pydrake.visualization.MeshcatPoseSliders_[AutoDiffXd], meshcat: pydrake.geometry.Meshcat, initial_pose: pydrake.math.RigidTransform = RigidTransform(
R=RotationMatrix([

[1.0, 0.0, 0.0], [0.0, 1.0, 0.0], [0.0, 0.0, 1.0],

]), p=[0.0, 0.0, 0.0],

), lower_limit: numpy.ndarray[numpy.float64[6, 1]] = array([-3.14159265, -3.14159265, -3.14159265, -1. , -1. ,

-1. ]), upper_limit: numpy.ndarray[numpy.float64[6, 1]] = array([3.14159265, 3.14159265, 3.14159265, 1. , 1. , 1. ]), step: numpy.ndarray[numpy.float64[6, 1]] = array([0.01, 0.01, 0.01, 0.01, 0.01, 0.01]), decrement_keycodes: List[str] = [‘KeyQ’, ‘KeyS’, ‘KeyA’, ‘KeyJ’, ‘KeyK’, ‘KeyU’], increment_keycodes: List[str] = [‘KeyE’, ‘KeyW’, ‘KeyD’, ‘KeyL’, ‘KeyI’, ‘KeyO’], prefix: str = ‘’, visible: numpy.ndarray[bool[6, 1]] = array([ True, True, True, True, True, True])) -> None

Creates MeshCat sliders for a roll-pitch-yaw-x-y-z parameterization of a pose (aka RigidTransform).

Parameter meshcat:

The MeshCat instance where the sliders will be added.

Parameter initial_pose:

(Optional) If provided, the sliders’ initial values will be as given.

Parameter lower_limit:

(Optional) The lower limit of the sliders for roll, pitch, yaw, x, y, z.

Parameter upper_limit:

(Optional) The upper limit of the sliders for roll, pitch, yaw, x, y, z.

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 6.

Parameter decrement_keycodes:

(Optional) A vector of length 6 with keycodes to assign to decrement the value of each slider (roll, pitch, yaw, x, y, z). See Meshcat::AddSlider for more details.

Parameter increment_keycodes:

(Optional) A vector of length 6 with keycodes to assign to increment the value of each slider (roll, pitch, yaw, x, y, z). See Meshcat::AddSlider for more details.

Parameter prefix:

(Optional) By default, the sliders will be named “roll, pitch, yaw, x, y, z”. If prefix is non-empty, the the sliders will be named “{prefix}_roll, {prefix}_pitch”, etc.

Parameter visible:

(Optional) If provided, determines which of the sliders (roll, pitch, yaw, x, y, z) are visible in the Meshcat window. This can be useful, for instance, if one only wants to control the pose in 2D (and therefore only show the sliders for e.g. yaw, x, and y).

The default keycodes provide the following keyboard mapping:

Click to expand C++ code...
┌───────┬┬───────┬┬───────┐        ┌───────┬┬───────┬┬───────┐
│   Q   ││   W   ││   E   │        │   U   ││   I   ││   O   │
│ roll- ││ pitch+││ roll+ │        │   z-  ││   y+  ││   z+  │
├───────┼┼───────┼┼───────┤        ├───────┼┼───────┼┼───────┤
├───────┼┼───────┼┼───────┤        ├───────┼┼───────┼┼───────┤
│   A   ││   S   ││   D   │        │   J   ││   K   ││   L   │
│  yaw- ││ pitch-││  yaw+ │        │   x-  ││   y-  ││   x+  │
└───────┴┴───────┴┴───────┘        └───────┴┴───────┴┴───────┘
Delete(self: pydrake.visualization.MeshcatPoseSliders_[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.visualization.MeshcatPoseSliders_[AutoDiffXd], system: pydrake.systems.framework.System_[AutoDiffXd], context: pydrake.systems.framework.Context_[AutoDiffXd], timeout: Optional[float] = None, stop_button_keycode: str = 'Escape') pydrake.math.RigidTransform

Publishes the given systems::System (typically, a Diagram including visualizers, 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 context:

The systems::Context for the systems::Diagram.

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 most recently output pose.

Precondition:

system must be this MeshcatPoseSliders system or be a top-level (i.e., “root”) diagram that contains this MeshcatPoseSliders system.

SetPose(self: pydrake.visualization.MeshcatPoseSliders_[AutoDiffXd], pose: pydrake.math.RigidTransform) None

Sets the pose to X. The MeshCat sliders will have their value updated. Additionally, the “initial pose” tracked by this instance will be updated to X. This “initial pose” update will persist even if sliders are removed (e.g., via Delete).

class pydrake.visualization.ModelVisualizer(*, visualize_frames=False, triad_length=0.3, triad_radius=0.005, triad_opacity=0.9, publish_contacts=True, show_rgbd_sensor=False, browser_new=False, pyplot=False, meshcat=None, environment_map: pathlib.Path = PosixPath('.'))

Bases: object

Visualizes models from a file or string buffer in MeshCat or Meldis.

To use this class to visualize model(s), create an instance with any desired options, add any models, and then call Run():

visualizer = ModelVisualizer(browser_new=True)
visualizer.AddModels(filename)
visualizer.Run()

The class also provides a parser() method to allow more complex Parser handling, e.g. adding a model from a string:

visualizer.parser().AddModelsFromString(buffer_containing_model, 'sdf')

This class may also be run as a standalone command-line tool using the pydrake.visualization.model_visualizer script, or via bazel run //tools:model_visualizer.

__init__(*, visualize_frames=False, triad_length=0.3, triad_radius=0.005, triad_opacity=0.9, publish_contacts=True, show_rgbd_sensor=False, browser_new=False, pyplot=False, meshcat=None, environment_map: pathlib.Path = PosixPath('.'))

Initializes a ModelVisualizer.

Parameters
  • visualize_frames – a flag that visualizes frames as triads for all links.

  • triad_length – the length of visualization triads.

  • triad_radius – the radius of visualization triads.

  • triad_opacity – the opacity of visualization triads.

  • publish_contacts – a flag for VisualizationConfig.

  • show_rgbd_sensor – when True, adds an RgbdSensor to the scene and pops up a local preview window of the rgb image. At the moment, the image display uses a native window so will not work in a remote or cloud runtime environment.

  • browser_new – a flag that will open the MeshCat display in a new browser window during Run().

  • pyplot – a flag that will open a pyplot figure for rendering using PlanarSceneGraphVisualizer.

  • meshcat – an existing Meshcat instance to re-use instead of creating a new instance. Useful in, e.g., Python notebooks.

AddModels(filename: Optional[pathlib.Path] = None, *, url: Optional[str] = None)

Adds all models found in an input file (or url).

This can be called multiple times, until the object is finalized.

Parameters
  • filename – the name of a file containing one or more models.

  • url – the package:// URL containing one or more models.

Exactly one of filename or url must be non-None.

Finalize(position=None)

Finalizes the object and sets up the visualization using the provided options once models have been added.

Parameters

position – a list of slider positions for the model(s); must match the number of positions in all model(s), including the 7 positions corresponding to any model bases that aren’t welded to the world.

meshcat()

Returns the Meshcat object this visualizer is plugged into. If none was provided in the constructor, this creates one on demand.

package_map()

Returns the PackageMap being used during parsing. Users should add entries here to be able to load models from non-Drake packages.

This method cannot be used after Finalize is called.

parser()

(Advanced) Returns a Parser that will load models into this visualizer.

Prefer to use package_map() and AddModels() to load models, instead of this method.

Calling this method will disable the “Reload” button in the visualizer, because we can no longer determine the scope of what to reload.

This method cannot be used after Finalize is called.

Run(position=None, loop_once=False)

Runs the model. If Finalize() hasn’t already been explicitly called then the object will be finalized first.

Will iterate once and exit if loop_once is True, otherwise will loop until the user quits.

Parameters
  • position – an ndarray-like list of slider positions for the model(s); must match the number of positions in all model(s), including the 7 positions corresponding to any model bases that aren’t welded to the world.

  • loop_once – a flag that exits the evaluation loop after one pass.

pydrake.visualization.plot_sublevelset_expression(ax, e, vertices=51, **kwargs)

Plots the 2D sub-level set e(x) <= 1, which must contain the origin.

Parameters
  • ax – the matplotlib axis to receive the plot

  • e – a symbolic expression in two variables

  • vertices – number of sample points along the boundary

  • kwargs – are passed to the matplotlib fill method

Returns

the return values from matplotlib’s fill command.

pydrake.visualization.plot_sublevelset_quadratic(ax, A, b=[0, 0], c=0, vertices=51, **kwargs)

Plots the 2D ellipse representing x’Ax + b’x + c <= 1, e.g. the one sub-level set of a quadratic form.

Parameters
  • ax – the matplotlib axis to receive the plot

  • A – an 2x2 PSD numpy array.

  • b – broadcastable to a 2x1 array

  • c – scalar

  • vertices – number of sample points along the boundary

  • kwargs – are passed to the matplotlib fill method

Returns

the return values from matplotlib’s fill command.

class pydrake.visualization.VideoWriter(*, filename, fps=16.0, backend='PIL', fourcc=None)

Bases: pydrake.systems.framework.LeafSystem

Publishes RgbdSensor output to a video file.

color_image→
VideoWriter

The video will contain recorded images from the color_image input port.

The methods AddToBuilder() or ConnectToRgbdSensor() make it easy to record color and/or depth and/or labels all at once. For companion systems, see also ColorizeDepthImage, ColorizeLabelImage, and ConcatenateImages.

This class delegates actual video output to one of two video backends, either “PIL” (aka Pillow) or “cv2”. PIL generally only supports image formats (e.g., gif, apng, webp) while cv2 also supports movies (e.g., mp4).

Warning

Once all images have been published, you must call video_writer.Save() to finish writing to the video file.

Warning

This class will fail at construction time if the specified backend module cannot be imported. You must ensure that whichever backend you choose is available in your environment. Drake neither bundles nor depends on either one.

__init__(*, filename, fps=16.0, backend='PIL', fourcc=None)

Constructs a VideoWriter system.

In many cases, the AddToBuilder() or ConnectRgbdSensor() methods might be easier to use than this constructor.

Parameters
  • filename – filename to write, e.g., "output.gif" or "output.mp4"

  • fps – the output video’s frame rate (in frames per second)

  • backend – which backend to use: “PIL” or “cv2”

  • fourcc – when using the cv2 backend, which encoder to use; good choices are “mp4v” or “avc1”; defaults to “mp4v”; refer to the OpenCV documentation for details.

static AddToBuilder(*, filename, builder, sensor_pose, fps=16.0, width=320, height=240, fov_y=0.5235987755982988, near=0.01, far=10.0, kinds=None, backend='PIL', fourcc=None)

Adds a RgbdSensor and VideoWriter system to the given builder, using a world-fixed pose. Returns the VideoWriter system.

See also ConnectRgbdSensor() in case you want to attach a VideoWriter to an already existing RgbdSensor (e.g., on attached to a robot).

Parameters
  • filename – filename to write, e.g., "output.gif" or "output.mp4"

  • builder – the DiagramBuilder

  • sensor_pose – the world-fixed position for the video camera

  • fps – the output video’s frame rate (in frames per second)

  • width – video camera width (in pixels)

  • height – video camera width (in pixels)

  • fov_y – video camera fov (in radians)

  • near – clipping plane distance (in meters)

  • far – clipping plane distance (in meters)

  • kinds – which image kind(s) to include in the video; valid options are "color", "label", and/or "depth"

  • backend – which backend to use: “PIL” or “cv2”.

  • fourcc – when using the cv2 backend, which encoder to use; good choices are “mp4v” or “avc1”; defaults to “mp4v” refer to the OpenCV documentation for details.

Warning

Once all images have been published, you must call video_writer.Save() to finish writing to the video file.

ConnectRgbdSensor(*, builder, sensor, kinds=None)

Adds a VideoWriter system to the given builder and connects it to the given RgbdSensor. Returns the VideoWriter system.

See also AddToBuilder() in case you want to record video from a world- fixed pose by creating a new sensor.

Parameters
  • builder – the DiagramBuilder

  • kinds – which image kind(s) to include in the video; valid options are "color", "label", and/or "depth"; when set to None, defaults to "color" only.

Warning

Once all images have been published, you must call video_writer.Save() to finish writing to the video file.

Save()

Flushes all images to the video file and closes the file.

Warning

Continuing a simulation after calling Save() will begin to overwrite the prior video with a new one.

class pydrake.visualization.VisualizationConfig

Settings for what MultibodyPlant and SceneGraph should send to Meshcat and/or Meldis.

See ApplyVisualizationConfig() for how to enact this configuration.

__init__(self: pydrake.visualization.VisualizationConfig, **kwargs) None
property default_illustration_color

The color to apply to any illustration geometry that hasn’t defined one. The vector must be of size three (rgb) or four (rgba).

property default_proximity_color

The color to apply to any proximity geometry that hasn’t defined one. The vector must be of size three (rgb) or four (rgba).

property delete_on_initialization_event

Determines whether to send a Meshcat::Delete() messages to the Meshcat object (if any) on an initialization event to remove any visualizations, e.g., from a previous simulation.

property enable_alpha_sliders

Determines whether to enable alpha sliders for geometry display.

property enable_meshcat_creation

Whether to create a Meshcat object if needed.

property initial_proximity_alpha

the effective transparency of the proximity geometry is the slider value multiplied by the alpha value of default_proximity_color. To have access to the full range of opacity, the color’s alpha value should be one and the slider should be used to change it.

Type

The initial value of the proximity alpha slider. Note

property lcm_bus

Which LCM URL to use.

See also

drake::systems::lcm::LcmBuses

property publish_contacts

Whether to show contact forces.

property publish_illustration

Whether to show illustration geometry.

property publish_inertia

Whether to show body inertia.

property publish_period

The duration (in seconds) between published LCM messages that update visualization. (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 publish_proximity

Whether to show proximity geometry.