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 pinocchio as pin
6 import numpy as np
7 import sys
8 import os
9 from os.path import dirname, join, abspath
10 
11 from pinocchio.visualize import MeshcatVisualizer
12 
13 # Load the URDF model.
14 # Conversion with str seems to be necessary when executing this file with ipython
15 pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))),"models")
16 
17 model_path = join(pinocchio_model_dir,"example-robot-data/robots")
18 mesh_dir = pinocchio_model_dir
19 urdf_filename = "talos_reduced.urdf"
20 urdf_model_path = join(join(model_path,"talos_data/robots"),urdf_filename)
21 
22 model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_model_path, mesh_dir, pin.JointModelFreeFlyer())
23 
24 viz = MeshcatVisualizer(model, collision_model, visual_model)
25 
26 # Start a new MeshCat server and client.
27 # Note: the server can also be started separately using the "meshcat-server" command in 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.initViewer(open=True)
34 except ImportError as err:
35  print("Error while initializing the viewer. It seems you should install Python meshcat")
36  print(err)
37  sys.exit(0)
38 
39 # Load the robot in the viewer.
40 viz.loadViewerModel()
41 
42 # Display a robot configuration.
43 q0 = pin.neutral(model)
44 viz.display(q0)
45 
46 # Display another robot.
47 viz2 = MeshcatVisualizer(model, collision_model, visual_model)
48 viz2.initViewer(viz.viewer)
49 viz2.loadViewerModel(rootNodeName = "pinocchio2")
50 q = q0.copy()
51 q[1] = 1.0
52 viz2.display(q)
53 


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04