meshcat-viewer-dae.py
Go to the documentation of this file.
1 # This examples shows how to load and move a robot in meshcat.
2 # Note: this feature requires Meshcat to be installed, this can be done using
3 # pip install --user meshcat
4 
5 import sys
6 from pathlib import Path
7 
8 import numpy as np
9 import pinocchio as pin
10 from pinocchio.visualize import MeshcatVisualizer
11 
12 # Load the URDF model.
13 # Conversion with str seems to be necessary when executing this file with ipython
14 pinocchio_model_dir = Path(__file__).parent.parent / "models"
15 
16 model_path = pinocchio_model_dir / "example-robot-data/robots"
17 mesh_dir = pinocchio_model_dir
18 urdf_filename = "romeo_small.urdf"
19 urdf_model_path = model_path / "romeo_description/urdf" / urdf_filename
20 
21 model, collision_model, visual_model = pin.buildModelsFromUrdf(
22  urdf_model_path, mesh_dir, pin.JointModelFreeFlyer()
23 )
24 
25 # Start a new MeshCat server and client.
26 # Note: the server can also be started separately using the "meshcat-server" command in
27 # a terminal:
28 # this enables the server to remain active after the current script ends.
29 #
30 # Option open=True pens the visualizer.
31 # Note: the visualizer can also be opened seperately by visiting the provided URL.
32 try:
33  viz = MeshcatVisualizer(model, collision_model, visual_model)
34  viz.initViewer(open=True)
35 except ImportError as err:
36  print(
37  "Error while initializing the viewer. "
38  "It seems you should install Python meshcat"
39  )
40  print(err)
41  sys.exit(0)
42 
43 # Load the robot in the viewer.
44 # Color is needed here because the Romeo URDF doesn't contain any color, so the default
45 # color results in an invisible robot (alpha value set to 0).
46 viz.loadViewerModel(color=[0.0, 0.0, 0.0, 1.0])
47 
48 # Display a robot configuration.
49 q0 = np.array(
50  [
51  0,
52  0,
53  0.840252,
54  0,
55  0,
56  0,
57  1, # Free flyer
58  0,
59  0,
60  -0.3490658,
61  0.6981317,
62  -0.3490658,
63  0, # left leg
64  0,
65  0,
66  -0.3490658,
67  0.6981317,
68  -0.3490658,
69  0, # right leg
70  0, # chest
71  1.5,
72  0.6,
73  -0.5,
74  -1.05,
75  -0.4,
76  -0.3,
77  -0.2, # left arm
78  0,
79  0,
80  0,
81  0, # head
82  1.5,
83  -0.6,
84  0.5,
85  1.05,
86  -0.4,
87  -0.3,
88  -0.2, # right arm
89  ]
90 ).T
91 viz.display(q0)
92 
93 # Display another robot.
94 red_robot_viz = MeshcatVisualizer(model, collision_model, visual_model)
95 red_robot_viz.initViewer(viz.viewer)
96 red_robot_viz.loadViewerModel(rootNodeName="red_robot", color=[1.0, 0.0, 0.0, 0.5])
97 q = q0.copy()
98 q[1] = 1.0
99 red_robot_viz.display(q)
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:576


pinocchio
Author(s):
autogenerated on Sun Dec 22 2024 03:41:11