meshcat-viewer-octree.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 
7 import hppfcl as fcl
8 import numpy as np
9 import pinocchio as pin
10 from pinocchio.visualize import MeshcatVisualizer
11 
12 if tuple(map(int, fcl.__version__.split("."))) >= (3, 0, 0):
13  with_octomap = fcl.WITH_OCTOMAP
14 else:
15  with_octomap = False
16 if not with_octomap:
17  print(
18  "This example is skiped as HPP-FCL has not been compiled with octomap support."
19  )
20 
21 model = pin.Model()
22 collision_model = pin.GeometryModel()
23 
24 octree = fcl.makeOctree(np.random.rand(1000, 3), 0.01)
25 octree_object = pin.GeometryObject("octree", 0, pin.SE3.Identity(), octree)
26 octree_object.meshColor[0] = 1.0
27 collision_model.addGeometryObject(octree_object)
28 
29 visual_model = collision_model
30 viz = MeshcatVisualizer(model, collision_model, visual_model)
31 
32 # Start a new MeshCat server and client.
33 # Note: the server can also be started separately using the "meshcat-server" command in
34 # a terminal:
35 # this enables the server to remain active after the current script ends.
36 #
37 # Option open=True pens the visualizer.
38 # Note: the visualizer can also be opened seperately by visiting the provided URL.
39 try:
40  viz.initViewer(open=True)
41 except ImportError as err:
42  print(
43  "Error while initializing the viewer. "
44  "It seems you should install Python meshcat"
45  )
46  print(err)
47  sys.exit(0)
48 
49 viz.loadViewerModel()
50 viz.clearDefaultLights()
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:540


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