manipulation.station

manipulation.station.AddPointClouds(*, scenario, station, builder, poses_output_port=None, meshcat=None)

Adds one DepthImageToPointCloud system to the builder for each camera in scenario, and connects it to the respective camera station output ports.

Parameters:
  • scenario (Scenario) – A Scenario structure, populated using the LoadScenario method.

  • station (Diagram) – A HardwareStation system (e.g. from MakeHardwareStation) that has already been added to builder.

  • builder (DiagramBuilder) – The DiagramBuilder containing station into which the new systems will be added.

  • poses_output_port (OutputPort | None) – (optional) HardwareStation will have a body_poses output port iff it was created with hardware=False. Alternatively, one could create a MultibodyPositionsToGeometryPoses system to consume the position measurements; this optional input can be used to support that workflow.

  • meshcat (Meshcat | None) – If not None, then a MeshcatPointCloudVisualizer will be added to the builder using this meshcat instance.

Returns:

A mapping from camera name to the DepthImageToPointCloud system.

Return type:

Mapping[str, DepthImageToPointCloud]

manipulation.station.AppendDirectives(scenario, *, filename=None, data=None, scenario_name=None)

Append additional directives to an existing scenario.

Parameters:
  • scenario (Scenario) – The scenario to append to.

  • filename (str | None) – A yaml filename to load the directives from.

  • data (str | None) – A yaml string to load the directives from. If both filename and string are specified, then the filename is parsed first, and then the string is _also_ parsed, presumably overwriting any directives from the filename.

  • scenario_name (str | None) – The name of the scenario/child to load from the yaml file. If None, then the entire file is loaded.

Returns:

The scenario with the additional directives appended.

Return type:

Scenario

class manipulation.station.Directives(directives=<factory>)

Defines the YAML format for directives to be applied to a Scenario.

Parameters:

directives (List[ModelDirective]) – A list of ModelDirective objects.

class manipulation.station.InverseDynamicsDriver

A simulation-only driver that adds the InverseDynamicsController to the station and exports the output ports. Multiple model instances can be driven with a single controller using instance_name1+instance_name2 as the key; the output ports will be named similarly.

class manipulation.station.JointPdControllerGains(kp=0, kd=0)

Defines the Proportional-Derivative gains for a single joint.

Parameters:
  • kp (float) – The proportional gain.

  • kd (float) – The derivative gain.

class manipulation.station.JointStiffnessDriver(gains=<factory>, hand_model_name='')

A simulation-only driver that sets up MultibodyPlant to act as if it is being controlled with a JointStiffnessController. The MultibodyPlant must be using SAP as the (discrete-time) contact solver.

Parameters:
  • gains (Mapping[str, JointPdControllerGains]) – A mapping of {actuator_name: JointPdControllerGains} for each actuator that should be controlled.

  • hand_model_name (str) – If set, then the gravity compensation will be turned off for this model instance (e.g. for a hand).

manipulation.station.LoadScenario(*, filename=None, data=None, scenario_name=None, defaults=Scenario(random_seed=0, simulation_duration=inf, simulator_config=SimulatorConfig(integration_scheme='runge_kutta3', max_step_size=0.01, accuracy=0.01, use_error_control=False, target_realtime_rate=0.0, publish_every_time_step=False), plant_config=MultibodyPlantConfig(time_step=0.001, penetration_allowance=0.001, stiction_tolerance=0.001, contact_model='hydroelastic_with_fallback', discrete_contact_approximation='sap', discrete_contact_solver='', sap_near_rigid_threshold=1.0, contact_surface_representation='polygon', adjacent_bodies_collision_filters=True), directives=[], lcm_buses={'default': DrakeLcmParams(lcm_url='memq://null', channel_suffix='', defer_initialization=False)}, model_drivers={}, cameras={}, visualization=VisualizationConfig(lcm_bus='default', publish_period=0.015625, publish_illustration=True, default_illustration_color=Rgba(r=0.9, g=0.9, b=0.9, a=1.0), publish_proximity=True, default_proximity_color=Rgba(r=0.8, g=0.0, b=0.0, a=1.0), initial_proximity_alpha=0.5, publish_contacts=True, publish_inertia=True, enable_meshcat_creation=True, delete_on_initialization_event=True, enable_alpha_sliders=False)))

Implements the command-line handling logic for scenario data.

Parameters:
  • filename (str | None) – A yaml filename to load the scenario from.

  • data (str | None) – A yaml _string_ to load the scenario from. If both filename and string are specified, then the filename is parsed first, and then the string is _also_ parsed, potentially overwriting defaults from the filename. Note: this will not append additional directives, it will replace them; see AppendDirectives.

  • scenario_name (str | None) – The name of the scenario/child to load from the yaml file. If None, then the entire file is loaded.

  • defaults (Scenario) – A Scenario object to use as the default values.

Returns:

A Scenario object loaded from the given input arguments.

Return type:

Scenario

manipulation.station.MakeHardwareStation(scenario, meshcat=None, *, package_xmls=[], hardware=False, parser_preload_callback=None, parser_prefinalize_callback=None, prebuild_callback=None)

Make a diagram encapsulating a simulation of (or the communications interface to/from) a physical robot, including sensors and controllers.

Parameters:
  • scenario (Scenario) – A Scenario structure, populated using the LoadScenario method.

  • meshcat (Meshcat | None) – If not None, then ApplyVisualizationConfig will called to add visualizers to the subdiagram using this meshcat instance.

  • package_xmls (List[str]) – A list of package.xml file paths that will be passed to the parser, using Parser.AddPackageXml().

  • hardware (bool) – If True, then the HardwareStationInterface diagram will be returned. Otherwise, the HardwareStation diagram will be returned.

  • parser_preload_callback (Callable[[Parser], None] | None) – A callback function that will be called after the Parser is created, but before any directives are processed. This can be used to add additional packages to the parser, or to add additional model directives.

  • parser_prefinalize_callback (Callable[[Parser], None] | None) – A callback function that will be called after the directives are processed, but before the plant is finalized. This can be used to add additional model directives.

  • prebuild_callback (Callable[[DiagramBuilder], None] | None) – A callback function that will be called after the diagram builder is created, but before the diagram is built. This can be used to add additional systems to the diagram.

Returns:

If hardware=False, (the default) returns a HardwareStation diagram containing: - A MultibodyPlant with populated via the directives in scenario. - A SceneGraph - The default Drake visualizers - Any robot / sensors drivers specified in the YAML description.

If hardware=True, returns a HardwareStationInterface diagram containing the network interfaces to communicate directly with the hardware drivers.

Return type:

Diagram

manipulation.station.MakeMultibodyPlant(scenario, *, model_instance_names=None, add_frozen_child_instances=False, package_xmls=[], parser_preload_callback=None, parser_prefinalize_callback=None)

Use a scenario to create a MultibodyPlant. This is intended, e.g., to facilitate easily building subsets of a scenario, for instance, to make a plant for a controller.

Parameters:
  • scenario (Scenario) – A Scenario structure, populated using the load_scenario method.

  • model_instance_names (List[str] | None) – If specified, then only the named model instances will be added to the plant. Otherwise, all model instances will be added. add_weld directives connecting added model instances to each other or to the world are also preserved.

  • add_frozen_child_instances (bool) – If True and model_instance_names is not None, then model_instances that are not listed in model_instance_names, but are welded to a model_instance that is listed, will be added to the plant; with all joints replaced by welded joints.

  • package_xmls (List[str]) – A list of package.xml file paths that will be passed to the parser, using Parser.AddPackageXml().

  • parser_preload_callback (Callable[[Parser], None] | None) – A callback function that will be called after the Parser is created, but before any directives are processed. This can be used to add additional packages to the parser, or to add additional model directives.

  • parser_prefinalize_callback (Callable[[Parser], None] | None) – A callback function that will be called after the directives are processed, but before the plant is finalized. This can be used to add additional model directives.

Returns:

A MultibodyPlant populated from (a subset of) the scenario.

Return type:

MultibodyPlant

manipulation.station.MakeRobotDiagram(scenario, *, model_instance_names=None, add_frozen_child_instances=True, package_xmls=[], parser_preload_callback=None, parser_prefinalize_callback=None)

Use a scenario to create a RobotDiagram (MultibodyPlant + SceneGraph). This is intended, e.g., to facilitate easily building subsets of a scenario, for instance, to make a plant for a controller which needs to make collision queries.

Parameters:
  • scenario (Scenario) – A Scenario structure, populated using the load_scenario method.

  • model_instance_names (List[str] | None) – If specified, then only the named model instances will be added to the plant. Otherwise, all model instances will be added.

  • add_frozen_child_instances (bool) – If True and model_instance_names is not None, then model_instances that are not listed in model_instance_names, but are welded to a model_instance that is listed, will be added to the plant; with all joints replaced by welded joints.

  • package_xmls (List[str]) – A list of package.xml file paths that will be passed to the parser, using Parser.AddPackageXml().

  • parser_preload_callback (Callable[[Parser], None] | None) – A callback function that will be called after the Parser is created, but before any directives are processed. This can be used to add additional packages to the parser, or to add additional model directives.

  • parser_prefinalize_callback (Callable[[Parser], None] | None) – A callback function that will be called after the directives are processed, but before the plant is finalized. This can be used to add additional model directives.

Returns:

A RobotDiagram populated from (a subset of) the scenario.

Return type:

RobotDiagram

manipulation.station.NegatedPort(builder, output_port, prefix='')

Negates the output of the given port.

Parameters:
  • builder (DiagramBuilder) – The diagram builder to add the negation system to.

  • output_port (OutputPort) – The output port to negate.

  • prefix (str) – The prefix to use for the negation system.

Returns:

The output port of the negation system.

Return type:

OutputPort

class manipulation.station.Scenario(random_seed=0, simulation_duration=inf, simulator_config=SimulatorConfig(integration_scheme='runge_kutta3', max_step_size=0.01, accuracy=0.01, use_error_control=False, target_realtime_rate=0.0, publish_every_time_step=False), plant_config=MultibodyPlantConfig(time_step=0.001, penetration_allowance=0.001, stiction_tolerance=0.001, contact_model='hydroelastic_with_fallback', discrete_contact_approximation='sap', discrete_contact_solver='', sap_near_rigid_threshold=1.0, contact_surface_representation='polygon', adjacent_bodies_collision_filters=True), directives=<factory>, lcm_buses=<factory>, model_drivers=<factory>, cameras=<factory>, visualization=VisualizationConfig(lcm_bus='default', publish_period=0.015625, publish_illustration=True, default_illustration_color=Rgba(r=0.9, g=0.9, b=0.9, a=1.0), publish_proximity=True, default_proximity_color=Rgba(r=0.8, g=0.0, b=0.0, a=1.0), initial_proximity_alpha=0.5, publish_contacts=True, publish_inertia=True, enable_meshcat_creation=True, delete_on_initialization_event=True, enable_alpha_sliders=False))

Defines the YAML format for a (possibly stochastic) scenario to be simulated.

Parameters:
  • random_seed (int) – Random seed for any random elements in the scenario. The seed is always deterministic in the Scenario; a caller who wants randomness must populate this value from their own randomness.

  • simulation_duration (float) – The maximum simulation time (in seconds). The simulator will attempt to run until this time and then terminate.

  • simulator_config (SimulatorConfig) – Simulator configuration (integrator and publisher parameters).

  • plant_config (MultibodyPlantConfig) – Plant configuration (time step and contact parameters).

  • directives (List[ModelDirective]) – All of the fully deterministic elements of the simulation.

  • lcm_buses (Mapping[str, DrakeLcmParams]) – A map of {bus_name: lcm_params} for LCM transceivers to be used by drivers, sensors, etc.

  • model_drivers (Mapping[str, IiwaDriver | InverseDynamicsDriver | JointStiffnessDriver | SchunkWsgDriver | ZeroForceDriver]) – For actuated models, specifies where each model’s actuation inputs come from, keyed on the ModelInstance name.

  • cameras (Mapping[str, CameraConfig]) – Cameras to add to the scene (and broadcast over LCM). The key for each camera is a helpful mnemonic, but does not serve a technical role. The CameraConfig::name field is still the name that will appear in the Diagram artifacts.

  • visualization (VisualizationConfig) – Visualization configuration.