visualizers.meshcat.visuals#

Module Contents#

visualizers.meshcat.visuals.DEFAULT_PREFIXES = ['actual', 'desired']#
visualizers.meshcat.visuals.DEFAULT_COLORS#
visualizers.meshcat.visuals.visualize_and_control_model(meshcat: pydrake.geometry.Meshcat, directives_filename: str, initial_joint_values: numpy.typing.ArrayLike | None = None, lower_joint_limits: numpy.typing.ArrayLike | None = None, upper_joint_limits: numpy.typing.ArrayLike | None = None) None#

Creates a visualization of a meshcat object with sliders attached to manipulate the joints.

Parameters:
  • meshcat (pydrake.geometry.Meshcat) –

  • directives_filename (str) –

  • initial_joint_values (Optional[numpy.typing.ArrayLike]) –

  • lower_joint_limits (Optional[numpy.typing.ArrayLike]) –

  • upper_joint_limits (Optional[numpy.typing.ArrayLike]) –

Return type:

None

class visualizers.meshcat.visuals.TrajectoryVisualizer(params: jacta.planner.core.parameter_container.ParameterContainer, sim_time_step: float)#
Parameters:
  • params (jacta.planner.core.parameter_container.ParameterContainer) –

  • sim_time_step (float) –

property meshcat: pydrake.geometry.Meshcat#
Return type:

pydrake.geometry.Meshcat

set_directives_prefix(model_directives: pydrake.multibody.parsing.ModelDirectives, prefix: str = 'directive::') None#

Add a prefix to rename the model directives. This function supports the “add_model” and “add_weld” directives.

Parameters:
  • model_directives (pydrake.multibody.parsing.ModelDirectives) – model directives to be renamed.

  • prefix (str) – the string that will be added in front of the names of all directives.

Return type:

None

set_color_of_models(plant: pydrake.multibody.plant.MultibodyPlant, model_instances: List[pydrake.multibody.tree.ModelInstanceIndex], scene_graph: pydrake.geometry.SceneGraph, color: pydrake.geometry.Rgba | float | None = None) None#

Set the color and transparency of the given model instances.

Parameters:
  • plant (pydrake.multibody.plant.MultibodyPlant) – the multibody plant that contains the model instances.

  • model_instances (List[pydrake.multibody.tree.ModelInstanceIndex]) – the model instance that will be recolored.

  • scene_graph (pydrake.geometry.SceneGraph) – the scene graph to be modified.

  • color (Optional[Union[pydrake.geometry.Rgba, float]]) – the new color and transparency as Rgba or just the transparency as a float (between 0 and 1),

  • colors (if we want to keep the original) –

Return type:

None

setup_and_connect(trajectories: List[pydrake.trajectories.PiecewisePolynomial.FirstOrderHold]) None#
Parameters:

trajectories (List[pydrake.trajectories.PiecewisePolynomial.FirstOrderHold]) –

Return type:

None

update_trajectories(trajectories: List[pydrake.trajectories.PiecewisePolynomial.FirstOrderHold]) None#
Parameters:

trajectories (List[pydrake.trajectories.PiecewisePolynomial.FirstOrderHold]) –

Return type:

None

visualize_trajectories(trajectories: List[pydrake.trajectories.PiecewisePolynomial.FirstOrderHold], prefixes: List[str], colors: Dict[str, float | pydrake.geometry.Rgba] | None = None) None#
Parameters:
  • trajectories (List[pydrake.trajectories.PiecewisePolynomial.FirstOrderHold]) –

  • prefixes (List[str]) –

  • colors (Optional[Dict[str, Union[float, pydrake.geometry.Rgba]]]) –

Return type:

None

show(trajectory: torch.FloatTensor, goal_state: torch.FloatTensor | None = None, colors: Dict[str, float | pydrake.geometry.Rgba] | None = DEFAULT_COLORS) None#
Parameters:
  • trajectory (torch.FloatTensor) –

  • goal_state (Optional[torch.FloatTensor]) –

  • colors (Optional[Dict[str, Union[float, pydrake.geometry.Rgba]]]) –

Return type:

None