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 visualizationInteractive 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

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
63 # Load URDF.
64 #
65 # This takes either a yourdfpy.URDF object or a path to a .urdf file.
66 urdf = load_robot_description(
67 robot_type + "_description",
68 load_meshes=load_meshes,
69 build_scene_graph=load_meshes,
70 load_collision_meshes=load_collision_meshes,
71 build_collision_scene_graph=load_collision_meshes,
72 )
73 viser_urdf = ViserUrdf(
74 server,
75 urdf_or_path=urdf,
76 load_meshes=load_meshes,
77 load_collision_meshes=load_collision_meshes,
78 collision_mesh_color_override=(1.0, 0.0, 0.0, 0.5),
79 )
80
81 # Create sliders in GUI that help us move the robot joints.
82 with server.gui.add_folder("Joint position control"):
83 (slider_handles, initial_config) = create_robot_control_sliders(
84 server, viser_urdf
85 )
86
87 # Add visibility checkboxes.
88 with server.gui.add_folder("Visibility"):
89 show_meshes_cb = server.gui.add_checkbox(
90 "Show meshes",
91 viser_urdf.show_visual,
92 )
93 show_collision_meshes_cb = server.gui.add_checkbox(
94 "Show collision meshes", viser_urdf.show_collision
95 )
96
97 @show_meshes_cb.on_update
98 def _(_):
99 viser_urdf.show_visual = show_meshes_cb.value
100
101 @show_collision_meshes_cb.on_update
102 def _(_):
103 viser_urdf.show_collision = show_collision_meshes_cb.value
104
105 # Hide checkboxes if meshes are not loaded.
106 show_meshes_cb.visible = load_meshes
107 show_collision_meshes_cb.visible = load_collision_meshes
108
109 # Set initial robot configuration.
110 viser_urdf.update_cfg(np.array(initial_config))
111
112 # Create grid.
113 trimesh_scene = viser_urdf._urdf.scene or viser_urdf._urdf.collision_scene
114 server.scene.add_grid(
115 "/grid",
116 width=2,
117 height=2,
118 position=(
119 0.0,
120 0.0,
121 # Get the minimum z value of the trimesh scene.
122 trimesh_scene.bounds[0, 2] if trimesh_scene is not None else 0.0,
123 ),
124 )
125
126 # Create joint reset button.
127 reset_button = server.gui.add_button("Reset")
128
129 @reset_button.on_click
130 def _(_):
131 for s, init_q in zip(slider_handles, initial_config):
132 s.value = init_q
133
134 # Sleep forever.
135 while True:
136 time.sleep(10.0)
137
138
139if __name__ == "__main__":
140 tyro.cli(main)