URDF robot visualizer

Visualize robot models from URDF files with interactive joint controls.

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

Features:

  • viser.extras.ViserUrdf for URDF file parsing and visualization

  • Interactive joint sliders for robot articulation

  • Real-time robot pose updates

  • Support for local URDF files and robot_descriptions library

Source: examples/04_demos/02_urdf_visualizer.py

URDF robot visualizer

Code

  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    slider_handles: list[viser.GuiInputHandle[float]] = []
 18    initial_config: list[float] = []
 19    for joint_name, (
 20        lower,
 21        upper,
 22    ) in viser_urdf.get_actuated_joint_limits().items():
 23        lower = lower if lower is not None else -np.pi
 24        upper = upper if upper is not None else np.pi
 25        initial_pos = 0.0 if lower < -0.1 and upper > 0.1 else (lower + upper) / 2.0
 26        slider = server.gui.add_slider(
 27            label=joint_name,
 28            min=lower,
 29            max=upper,
 30            step=1e-3,
 31            initial_value=initial_pos,
 32        )
 33        slider.on_update(  # When sliders move, we update the URDF configuration.
 34            lambda _: viser_urdf.update_cfg(
 35                np.array([slider.value for slider in slider_handles])
 36            )
 37        )
 38        slider_handles.append(slider)
 39        initial_config.append(initial_pos)
 40    return slider_handles, initial_config
 41
 42
 43def main(
 44    robot_type: Literal[
 45        "panda",
 46        "ur10",
 47        "cassie",
 48        "allegro_hand",
 49        "barrett_hand",
 50        "robotiq_2f85",
 51        "atlas_drc",
 52        "g1",
 53        "h1",
 54        "anymal_c",
 55        "go2",
 56    ] = "panda",
 57    load_meshes: bool = True,
 58    load_collision_meshes: bool = False,
 59) -> None:
 60    # Start viser server.
 61    server = viser.ViserServer()
 62    server.initial_camera.position = (1.2, 1.2, 1.2)
 63
 64    # Load URDF.
 65    #
 66    # This takes either a yourdfpy.URDF object or a path to a .urdf file.
 67    urdf = load_robot_description(
 68        robot_type + "_description",
 69        load_meshes=load_meshes,
 70        build_scene_graph=load_meshes,
 71        load_collision_meshes=load_collision_meshes,
 72        build_collision_scene_graph=load_collision_meshes,
 73    )
 74    viser_urdf = ViserUrdf(
 75        server,
 76        urdf_or_path=urdf,
 77        load_meshes=load_meshes,
 78        load_collision_meshes=load_collision_meshes,
 79        collision_mesh_color_override=(1.0, 0.0, 0.0, 0.5),
 80    )
 81
 82    # Create sliders in GUI that help us move the robot joints.
 83    with server.gui.add_folder("Joint position control"):
 84        (slider_handles, initial_config) = create_robot_control_sliders(
 85            server, viser_urdf
 86        )
 87
 88    # Add visibility checkboxes.
 89    with server.gui.add_folder("Visibility"):
 90        show_meshes_cb = server.gui.add_checkbox(
 91            "Show meshes",
 92            viser_urdf.show_visual,
 93        )
 94        show_collision_meshes_cb = server.gui.add_checkbox(
 95            "Show collision meshes", viser_urdf.show_collision
 96        )
 97
 98    @show_meshes_cb.on_update
 99    def _(_):
100        viser_urdf.show_visual = show_meshes_cb.value
101
102    @show_collision_meshes_cb.on_update
103    def _(_):
104        viser_urdf.show_collision = show_collision_meshes_cb.value
105
106    # Hide checkboxes if meshes are not loaded.
107    show_meshes_cb.visible = load_meshes
108    show_collision_meshes_cb.visible = load_collision_meshes
109
110    # Set initial robot configuration.
111    viser_urdf.update_cfg(np.array(initial_config))
112
113    # Create grid.
114    trimesh_scene = viser_urdf._urdf.scene or viser_urdf._urdf.collision_scene
115    server.scene.add_grid(
116        "/grid",
117        width=2,
118        height=2,
119        position=(
120            0.0,
121            0.0,
122            # Get the minimum z value of the trimesh scene.
123            trimesh_scene.bounds[0, 2] if trimesh_scene is not None else 0.0,
124        ),
125    )
126
127    # Create joint reset button.
128    reset_button = server.gui.add_button("Reset")
129
130    @reset_button.on_click
131    def _(_):
132        for s, init_q in zip(slider_handles, initial_config):
133            s.value = init_q
134
135    # Sleep forever.
136    while True:
137        time.sleep(10.0)
138
139
140if __name__ == "__main__":
141    tyro.cli(main)