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