Robot URDF visualizerΒΆ

Requires yourdfpy and robot_descriptions. Any URDF supported by yourdfpy should work.

The viser.extras.ViserUrdf is a lightweight interface between yourdfpy and viser. It can also take a path to a local URDF file as input.

 1from __future__ import annotations
 2
 3import time
 4from typing import Literal
 5
 6import numpy as np
 7import tyro
 8from robot_descriptions.loaders.yourdfpy import load_robot_description
 9
10import viser
11from viser.extras import ViserUrdf
12
13
14def create_robot_control_sliders(
15    server: viser.ViserServer, viser_urdf: ViserUrdf
16) -> tuple[list[viser.GuiInputHandle[float]], list[float]]:
17    """Create slider for each joint of the robot. We also update robot model
18    when slider moves."""
19    slider_handles: list[viser.GuiInputHandle[float]] = []
20    initial_config: list[float] = []
21    for joint_name, (
22        lower,
23        upper,
24    ) in viser_urdf.get_actuated_joint_limits().items():
25        lower = lower if lower is not None else -np.pi
26        upper = upper if upper is not None else np.pi
27        initial_pos = 0.0 if lower < 0 and upper > 0 else (lower + upper) / 2.0
28        slider = server.gui.add_slider(
29            label=joint_name,
30            min=lower,
31            max=upper,
32            step=1e-3,
33            initial_value=initial_pos,
34        )
35        slider.on_update(  # When sliders move, we update the URDF configuration.
36            lambda _: viser_urdf.update_cfg(
37                np.array([slider.value for slider in slider_handles])
38            )
39        )
40        slider_handles.append(slider)
41        initial_config.append(initial_pos)
42    return slider_handles, initial_config
43
44
45def main(
46    robot_type: Literal[
47        "panda",
48        "ur10",
49        "cassie",
50        "allegro_hand",
51        "barrett_hand",
52        "robotiq_2f85",
53        "atlas_drc",
54        "g1",
55        "h1",
56        "anymal_c",
57        "go2",
58    ] = "panda",
59) -> None:
60    # Start viser server.
61    server = viser.ViserServer()
62
63    # Load URDF.
64    #
65    # This takes either a yourdfpy.URDF object or a path to a .urdf file.
66    viser_urdf = ViserUrdf(
67        server,
68        urdf_or_path=load_robot_description(robot_type + "_description"),
69    )
70
71    # Create sliders in GUI that help us move the robot joints.
72    with server.gui.add_folder("Joint position control"):
73        (slider_handles, initial_config) = create_robot_control_sliders(
74            server, viser_urdf
75        )
76
77    # Set initial robot configuration.
78    viser_urdf.update_cfg(np.array(initial_config))
79
80    # Create joint reset button.
81    reset_button = server.gui.add_button("Reset")
82
83    @reset_button.on_click
84    def _(_):
85        for s, init_q in zip(slider_handles, initial_config):
86            s.value = init_q
87
88    # Sleep forever.
89    while True:
90        time.sleep(10.0)
91
92
93if __name__ == "__main__":
94    tyro.cli(main)