meshcat-viewer.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 = "talos_reduced.urdf"
19 # urdf_model_path = join(join(model_path,"talos_data/robots"),urdf_filename)
20 urdf_filename = "solo.urdf"
21 urdf_model_path = model_path / "solo_description/robots" / urdf_filename
22 
23 model, collision_model, visual_model = pin.buildModelsFromUrdf(
24  urdf_model_path, mesh_dir, pin.JointModelFreeFlyer()
25 )
26 
27 # Start a new MeshCat server and client.
28 # Note: the server can also be started separately using the "meshcat-server" command in
29 # a terminal:
30 # this enables the server to remain active after the current script ends.
31 #
32 # Option open=True pens the visualizer.
33 # Note: the visualizer can also be opened seperately by visiting the provided URL.
34 try:
35  viz = MeshcatVisualizer(model, collision_model, visual_model)
36  viz.initViewer(open=True)
37 except ImportError as err:
38  print(
39  "Error while initializing the viewer. "
40  "It seems you should install Python meshcat"
41  )
42  print(err)
43  sys.exit(0)
44 
45 # Load the robot in the viewer.
46 viz.loadViewerModel()
47 
48 # Display a robot configuration.
49 q0 = pin.neutral(model)
50 viz.display(q0)
51 viz.displayVisuals(True)
52 
53 # Create a convex shape from solo main body
54 mesh = visual_model.geometryObjects[0].geometry
55 mesh.buildConvexRepresentation(True)
56 convex = mesh.convex
57 
58 # Place the convex object on the scene and display it
59 if convex is not None:
60  placement = pin.SE3.Identity()
61  placement.translation[0] = 2.0
62  geometry = pin.GeometryObject("convex", 0, placement, convex)
63  geometry.meshColor = np.ones(4)
64  # Add a PhongMaterial to the convex object
65  geometry.overrideMaterial = True
66  geometry.meshMaterial = pin.GeometryPhongMaterial()
67  geometry.meshMaterial.meshEmissionColor = np.array([1.0, 0.1, 0.1, 1.0])
68  geometry.meshMaterial.meshSpecularColor = np.array([0.1, 1.0, 0.1, 1.0])
69  geometry.meshMaterial.meshShininess = 0.8
70  visual_model.addGeometryObject(geometry)
71  # After modifying the visual_model we must rebuild
72  # associated data inside the visualizer
73  viz.rebuildData()
74 
75 # Display another robot.
76 viz2 = MeshcatVisualizer(model, collision_model, visual_model)
77 viz2.initViewer(viz.viewer)
78 viz2.loadViewerModel(rootNodeName="pinocchio2")
79 q = q0.copy()
80 q[1] = 1.0
81 viz2.display(q)
82 
83 # standing config
84 q1 = np.array(
85  [0.0, 0.0, 0.235, 0.0, 0.0, 0.0, 1.0, 0.8, -1.6, 0.8, -1.6, -0.8, 1.6, -0.8, 1.6]
86 )
87 
88 v0 = np.random.randn(model.nv) * 2
89 data = viz.data
90 pin.forwardKinematics(model, data, q1, v0)
91 frame_id = model.getFrameId("HR_FOOT")
92 viz.display()
93 viz.drawFrameVelocities(frame_id=frame_id)
94 
95 model.gravity.linear[:] = 0.0
96 dt = 0.01
97 
98 
99 def sim_loop():
100  tau0 = np.zeros(model.nv)
101  qs = [q1]
102  vs = [v0]
103  nsteps = 100
104  for i in range(nsteps):
105  q = qs[i]
106  v = vs[i]
107  a1 = pin.aba(model, data, q, v, tau0)
108  vnext = v + dt * a1
109  qnext = pin.integrate(model, q, dt * vnext)
110  qs.append(qnext)
111  vs.append(vnext)
112  viz.display(qnext)
113  viz.drawFrameVelocities(frame_id=frame_id)
114  return qs, vs
115 
116 
117 qs, vs = sim_loop()
118 
119 fid2 = model.getFrameId("FL_FOOT")
120 
121 
122 def my_callback(i, *args):
123  viz.drawFrameVelocities(frame_id)
124  viz.drawFrameVelocities(fid2)
125 
126 
127 with viz.create_video_ctx("../leap.mp4"):
128  viz.play(qs, dt, callback=my_callback)
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
meshcat-viewer.sim_loop
def sim_loop()
Definition: meshcat-viewer.py:99
meshcat-viewer.my_callback
def my_callback(i, *args)
Definition: meshcat-viewer.py:122
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:540


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:47