show_me¶
Submodules¶
Classes¶
- class brom_drake.productions.debug.show_me.show_me_system.ShowMeSystem(plant: MultibodyPlant, model_index: ModelInstanceIndex, desired_joint_positions: ndarray, **kwargs)[source]¶
Description
This class defines a LeafSystem that will force a specific model (model_index) in a MultibodyPlant to hold the joint positions provided to it as input.
The object may or may not be welded to the world frame.
Block Diagram
The ShowMeSystem block diagram is as follows:
|---------------| | | desired_joint_positions --->| ShowMeSystem |---> measured_joint_positions | | |---------------|
Parameters
- plantMultibodyPlant
The MultibodyPlant containing the model to be shown.
- model_indexModelInstanceIndex
The ModelInstanceIndex of the model to be shown.
- desired_joint_positionsnp.ndarray
The desired joint positions for the model, if any.
- SetModelJointPositions(context: Context, output: BasicVector)[source]¶
Description
This method will set the joint positions of the model to the desired joint positions.
Parameters
- context: Context
The context of the LeafSystem at the time that this callback is triggered.
- output: BasicVector
The output vector to be populated with the current joint positions.
- class brom_drake.productions.debug.show_me.show_me_this_model.ShowMeThisModel(path_to_model: str | Path, with_these_joint_positions: List[float] = None, base_link_name: str = None, time_step: float = 0.001, meshcat_port_number: int = 7001, show_collision_geometries: bool = False, **kwargs)[source]¶
Description
A production which allows the user to visualize a specified model in Meshcat, with the ability to set desired joint positions, if the model is a robot/articulated.
Parameters
- path_to_model: str
The path to the model file to be visualized. TODO: Add support for Path type. Make sure to add tests!!
- with_these_joint_positions: List[float], optional
A list of joint positions to set the model to when visualized. The length of this list must match the number of positions in the model. If None, the model will be visualized in its default configuration. Default is None.
- base_link_name: str, optional
The name of the base link of the model. If None, the production will attempt to automatically determine the base link name. Default is None.
- time_step: float, optional
The time step to use for the MultibodyPlant. Default is 1e-3.
- meshcat_port_number: int, optional
The port number to use for Meshcat visualization. If None, Meshcat visualization will be disabled. Default is 7001.
- show_collision_geometries: bool, optional
A boolean flag indicating whether to show collision geometries in Meshcat INSTEAD of the visual geometries. Default is False.
Usage
The production can be used to show both simple models (e.g., single objects) or articulated models (e.g., robots).
To show a simple model, simply provide the path to the model file.
from brom_drake.productions import ShowMeThisModel # Some stuff here urdf_file_path = "path/to/your/model.urdf" # Create the production production = ShowMeThisModel( urdf_file_path, time_step=1e-3, ) # Add the cast to the production, build the diagram, and simulate diagram, diagram_context = production.add_cast_and_build() # Set up simulation simulator = Simulator(diagram, diagram_context) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False)
If the model is articulated, then you can also provide desired joint positions.
from brom_drake.productions import ShowMeThisModel # Some stuff here urdf_file_path = "path/to/your/articulated_model.urdf" desired_joint_positions = [0.0, 1.0, -1.0, 0.5] # Example joint positions # Create the production production = ShowMeThisModel( urdf_file_path, with_these_joint_positions=desired_joint_positions, time_step=1e-3, ) # Add the cast to the production, build the diagram, and simulate diagram, diagram_context = production.add_cast_and_build() # Set up simulation simulator = Simulator(diagram, diagram_context) simulator.set_target_realtime_rate(1.0) simulator.set_publish_every_time_step(False)
- add_cast_and_build(cast: Tuple[Role, LeafSystem | Diagram] = []) Tuple[Diagram, Context][source]¶
Description
This method builds the production’s diagram and context, and assigns the plant context to the internal ShowMeSystem.
Parameters
- cast: Tuple[Role, Performer], optional
The cast to be added to the production. Default is an empty tuple.
Returns
- diagram: Diagram
The built Diagram of the production.
- diagram_context: Context
The built Context of the production.
- add_multibody_triads()[source]¶
Description
This method will add triads to the world frame and any other relevant frames.
- add_supporting_cast()[source]¶
Description
This method updates the production’s - MultibodyPlant with the user’s model - Using the ShowMeSystem to freeze the model in place - Connects to Meshcat, if requested
This is required to be implemented by all children of the BaseProduction class.
- create_and_connect_source_of_joint_positions()[source]¶
Description
This method will create and connect a source of joint positions to the ShowMeSystem.
Assumptions
self.show_me_systemis not Noneself.q_desis not None
- find_number_of_positions_in_model() int[source]¶
Description
This method will return the number of positions in the model as defined by the user (through the path_to_model).
Returns
- n_positions: int
The number of positions in the model.
- property id: ProductionID¶
Description
This property returns the unique identifier for this production. (i.e., ProductionID.kShowMeThisModel)
This is required to be implemented by all children of the BaseProduction class.
Returns
- id: ProductionID
The unique identifier for this production.
Functions¶
(None found)
Variables¶
(None found)