33import base64
44import warnings
55import xml .etree .ElementTree as Et
6- from typing import Optional , Any , Dict , Union , Type
6+ from typing import Optional , Any , Dict , Union , Type , Set
77
88import numpy as np
99
1010import meshcat
1111from meshcat .geometry import (
12- ReferenceSceneElement , Geometry , TriangularMeshGeometry , pack_numpy_array )
12+ ReferenceSceneElement , Geometry , TriangularMeshGeometry )
1313
1414import hppfcl
1515import pinocchio as pin
@@ -56,7 +56,7 @@ def __init__(self, height: float, radius: float, num_segments: int = 32):
5656 for side , rng in enumerate ([
5757 range (int (N // 4 ) + 1 ), range (int (N // 4 ), int (N // 2 ) + 1 )]):
5858 for i in rng :
59- for j in range (N + 1 ):
59+ for j in range (N ):
6060 theta = j * 2 * math .pi / N
6161 phi = math .pi * (i / (N // 2 ) - 1 / 2 )
6262 vertex = np .empty (3 )
@@ -71,26 +71,22 @@ def __init__(self, height: float, radius: float, num_segments: int = 32):
7171 faces = []
7272 for i in range (int (N // 2 ) + 1 ):
7373 for j in range (N ):
74- vec = np .array ([i * (N + 1 ) + j ,
75- i * (N + 1 ) + (j + 1 ),
76- (i + 1 ) * (N + 1 ) + (j + 1 ),
77- (i + 1 ) * (N + 1 ) + j ])
78- if i == N // 4 :
79- faces .append (vec [[0 , 2 , 3 ]])
80- faces .append (vec [[0 , 1 , 2 ]])
81- else :
82- faces .append (vec [[0 , 1 , 2 ]])
83- faces .append (vec [[0 , 2 , 3 ]])
74+ vec = np .array ([i * N + j ,
75+ i * N + (j + 1 ) % N ,
76+ (i + 1 ) * N + (j + 1 ) % N ,
77+ (i + 1 ) * N + j ])
78+ faces .append (vec [[0 , 1 , 2 ]])
79+ faces .append (vec [[0 , 2 , 3 ]])
8480 faces = np .vstack (faces )
8581
8682 # Init base class
8783 super ().__init__ (vertices , faces )
8884
89- # TODO: Make the cache local to the meshcat server
90- all_textures = set ()
9185
9286class DaeMeshGeometryWithTexture (ReferenceSceneElement ):
93- def __init__ (self , dae_path : str ) -> None :
87+ def __init__ (self ,
88+ dae_path : str ,
89+ cache : Optional [Set [str ]] = None ) -> None :
9490 """Load Collada files with texture images.
9591
9692 Inspired from
@@ -117,13 +113,17 @@ def __init__(self, dae_path: str) -> None:
117113 e .text for e in img_lib_element .iter ()
118114 if e .tag .count ('init_from' )]
119115
120- # Encode each texture in base64 for Three.js ColladaLoader to load it
116+ # Convert textures to data URL for Three.js ColladaLoader to load them
121117 self .img_resources = {}
122118 for img_path in img_resource_paths :
123- if img_path in all_textures :
124- self .img_resources [img_path ] = ""
125- continue
126- all_textures .add (img_path )
119+ # Return empty string if already in cache
120+ if cache is not None :
121+ if img_path in cache :
122+ self .img_resources [img_path ] = ""
123+ continue
124+ cache .add (img_path )
125+
126+ # Encode texture in base64
127127 img_path_abs = img_path
128128 if not os .path .isabs (img_path ):
129129 img_path_abs = os .path .normpath (
@@ -148,10 +148,10 @@ def lower(self) -> Dict[str, Any]:
148148 'materials' : [],
149149 'object' : {
150150 'uuid' : self .uuid ,
151- 'type' :'_meshfile_object' ,
151+ 'type' : '_meshfile_object' ,
152152 'format' : 'dae' ,
153153 'data' : self .dae_raw ,
154- 'resources' : self .img_resources # Very costly
154+ 'resources' : self .img_resources
155155 }
156156 }
157157 }
@@ -169,13 +169,16 @@ class MeshcatVisualizer(BaseVisualizer):
169169 """ # noqa: E501
170170 def initViewer (self ,
171171 viewer : meshcat .Visualizer = None ,
172+ cache : Optional [Set [str ]] = None ,
172173 loadModel : bool = False ,
173- mustOpen : bool = False ):
174+ mustOpen : bool = False ,
175+ ** kwargs : Any ) -> None :
174176 """Start a new MeshCat server and client.
175177 Note: the server can also be started separately using the
176178 "meshcat-server" command in a terminal: this enables the server to
177179 remain active after the current script ends.
178180 """
181+ self .cache = cache
179182 self .root_name = None
180183 self .visual_group = None
181184 self .collision_group = None
@@ -255,24 +258,23 @@ def loadPrimitive(self, geometry_object: hppfcl.CollisionGeometry):
255258
256259 def loadMesh (self , geometry_object : hppfcl .CollisionGeometry ):
257260 # Mesh path is empty if Pinocchio is built without HPP-FCL bindings
258- if geometry_object .meshPath == "" :
261+ mesh_path = geometry_object .meshPath
262+ if mesh_path == "" :
259263 msg = ("Display of geometric primitives is supported only if "
260264 "pinocchio is build with HPP-FCL bindings." )
261265 warnings .warn (msg , category = UserWarning , stacklevel = 2 )
262266 return None
263267
264268 # Get file type from filename extension
265- _ , file_extension = os .path .splitext (geometry_object . meshPath )
269+ _ , file_extension = os .path .splitext (mesh_path )
266270 if file_extension .lower () == ".dae" :
267- obj = DaeMeshGeometryWithTexture (geometry_object . meshPath )
271+ obj = DaeMeshGeometryWithTexture (mesh_path , self . cache )
268272 elif file_extension .lower () == ".obj" :
269- obj = meshcat .geometry .ObjMeshGeometry .from_file (
270- geometry_object .meshPath )
273+ obj = meshcat .geometry .ObjMeshGeometry .from_file (mesh_path )
271274 elif file_extension .lower () == ".stl" :
272- obj = meshcat .geometry .StlMeshGeometry .from_file (
273- geometry_object .meshPath )
275+ obj = meshcat .geometry .StlMeshGeometry .from_file (mesh_path )
274276 else :
275- msg = f"Unknown mesh file format: { geometry_object . meshPath } ."
277+ msg = f"Unknown mesh file format: { mesh_path } ."
276278 warnings .warn (msg , category = UserWarning , stacklevel = 2 )
277279 obj = None
278280
0 commit comments