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 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 import hppfcl as fcl
13 
14 if tuple(map(int, fcl.__version__.split("."))) >= (3, 0, 0):
15  with_octomap = fcl.WITH_OCTOMAP
16 else:
17  with_octomap = False
18 if not with_octomap:
19  print(
20  "This example is skiped as HPP-FCL has not been compiled with octomap support."
21  )
22 
23 model = pin.Model()
24 collision_model = pin.GeometryModel()
25 
26 octree = fcl.makeOctree(np.random.rand(1000, 3), 0.01)
27 octree_object = pin.GeometryObject("octree", 0, pin.SE3.Identity(), octree)
28 octree_object.meshColor[0] = 1.0
29 collision_model.addGeometryObject(octree_object)
30 
31 visual_model = collision_model
32 viz = MeshcatVisualizer(model, collision_model, visual_model)
33 
34 # Start a new MeshCat server and client.
35 # Note: the server can also be started separately using the "meshcat-server" command in 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. 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:532
path


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:39