1 from ..
import pinocchio_pywrap_default
as pin
2 from ..utils
import npToTuple
4 from .
import BaseVisualizer
9 from typing
import List
13 import meshcat.geometry
as mg
15 import_meshcat_succeed =
False
17 import_meshcat_succeed =
True
20 import xml.etree.ElementTree
as Et
23 from typing
import Optional, Any, Dict, Union, Set
25 MsgType = Dict[str, Union[str, bytes, bool, float,
"MsgType"]]
30 WITH_HPP_FCL_BINDINGS =
True
32 WITH_HPP_FCL_BINDINGS =
False
34 DEFAULT_COLOR_PROFILES = {
35 "gray": ([0.98, 0.98, 0.98], [0.8, 0.8, 0.8]),
36 "white": ([1.0, 1.0, 1.0], [1.0, 1.0, 1.0]),
38 COLOR_PRESETS = DEFAULT_COLOR_PROFILES.copy()
40 FRAME_AXIS_POSITIONS = (
41 np.array([[0, 0, 0], [1, 0, 0], [0, 0, 0], [0, 1, 0], [0, 0, 0], [0, 0, 1]])
46 np.array([[1, 0, 0], [1, 0.6, 0], [0, 1, 0], [0.6, 1, 0], [0, 0, 1], [0, 0.6, 1]])
53 assert color
is not None
54 color = np.asarray(color)
55 assert color.shape == (3,)
56 return color.clip(0.0, 1.0)
60 """Check whether the geometry object contains a Mesh supported by MeshCat"""
61 if geometry_object.meshPath ==
"":
64 _, file_extension = os.path.splitext(geometry_object.meshPath)
65 if file_extension.lower()
in [
".dae",
".obj",
".stl"]:
71 if import_meshcat_succeed:
74 """A cone of the given height and radius. By Three.js convention, the axis
75 of rotational symmetry is aligned with the y-axis.
82 radialSegments: float = 32,
83 openEnded: bool =
False,
91 def lower(self, object_data: Any) -> MsgType:
94 "type":
"ConeGeometry",
102 def __init__(self, dae_path: str, cache: Optional[Set[str]] =
None) ->
None:
103 """Load Collada files with texture images.
105 https://gist.github.com/danzimmerman/a392f8eadcf1166eb5bd80e3922dbdc5
115 dae_dir = os.path.dirname(dae_path)
116 with open(dae_path,
"r")
as text_file:
120 img_resource_paths = []
121 img_lib_element = Et.parse(dae_path).find(
122 "{http://www.collada.org/2005/11/COLLADASchema}library_images"
125 img_resource_paths = [
126 e.text
for e
in img_lib_element.iter()
if e.tag.count(
"init_from")
131 for img_path
in img_resource_paths:
133 if cache
is not None:
134 if img_path
in cache:
140 img_path_abs = img_path
141 if not os.path.isabs(img_path):
142 img_path_abs = os.path.normpath(os.path.join(dae_dir, img_path_abs))
143 if not os.path.isfile(img_path_abs):
144 raise UserWarning(f
"Texture '{img_path}' not found.")
145 with open(img_path_abs,
"rb")
as img_file:
146 img_data = base64.b64encode(img_file.read())
147 img_uri = f
"data:image/png;base64,{img_data.decode('utf-8')}"
151 """Pack data into a dictionary of the format that must be passed to
152 `Visualizer.window.send`.
155 "type":
"set_object",
158 "metadata": {
"version": 4.5,
"type":
"Object"},
163 "type":
"_meshfile_object",
177 """A plane of the given width and height."""
183 widthSegments: float = 1,
184 heightSegments: float = 1,
192 def lower(self, object_data: Any) -> MsgType:
195 "type":
"PlaneGeometry",
204 WITH_HPP_FCL_BINDINGS
205 and tuple(map(int, hppfcl.__version__.split(
"."))) >= (3, 0, 0)
206 and hppfcl.WITH_OCTOMAP
210 boxes = octree.toBoxes()
214 bs = boxes[0][3] / 2.0
215 num_boxes = len(boxes)
217 box_corners = np.array(
230 all_points = np.empty((8 * num_boxes, 3))
231 all_faces = np.empty((12 * num_boxes, 3), dtype=int)
233 for box_id, box_properties
in enumerate(boxes):
234 box_center = box_properties[:3]
236 corners = box_corners + box_center
237 point_range = range(box_id * 8, (box_id + 1) * 8)
238 all_points[point_range, :] = corners
249 all_faces[face_id] = np.array([C, D, B])
250 all_faces[face_id + 1] = np.array([B, A, C])
251 all_faces[face_id + 2] = np.array([A, B, F])
252 all_faces[face_id + 3] = np.array([F, E, A])
253 all_faces[face_id + 4] = np.array([E, F, H])
254 all_faces[face_id + 5] = np.array([H, G, E])
255 all_faces[face_id + 6] = np.array([G, H, D])
256 all_faces[face_id + 7] = np.array([D, C, G])
258 all_faces[face_id + 8] = np.array([A, E, G])
259 all_faces[face_id + 9] = np.array([G, C, A])
261 all_faces[face_id + 10] = np.array([B, H, F])
262 all_faces[face_id + 11] = np.array([H, B, D])
266 colors = np.empty((all_points.shape[0], 3))
267 colors[:] = np.ones(3)
268 mesh = mg.TriangularMeshGeometry(all_points, all_faces, colors)
273 raise NotImplementedError(
"loadOctree need hppfcl with octomap support")
276 if WITH_HPP_FCL_BINDINGS:
279 if isinstance(mesh, (hppfcl.HeightFieldOBBRSS, hppfcl.HeightFieldAABB)):
280 heights = mesh.getHeights()
281 x_grid = mesh.getXGrid()
282 y_grid = mesh.getYGrid()
283 min_height = mesh.getMinHeight()
285 X, Y = np.meshgrid(x_grid, y_grid)
290 num_cells = (nx) * (ny) * 2 + (nx + ny) * 4 + 2
292 num_vertices = X.size
295 faces = np.empty((num_tris, 3), dtype=int)
296 vertices = np.vstack(
300 X.reshape(num_vertices),
301 Y.reshape(num_vertices),
302 heights.reshape(num_vertices),
308 X.reshape(num_vertices),
309 Y.reshape(num_vertices),
310 np.full(num_vertices, min_height),
318 for y_id
in range(ny):
319 for x_id
in range(nx):
320 p0 = x_id + y_id * (nx + 1)
325 faces[face_id] = np.array([p0, p3, p1])
327 faces[face_id] = np.array([p3, p2, p1])
331 p0_low = p0 + num_vertices
332 p1_low = p1 + num_vertices
334 faces[face_id] = np.array([p0, p1_low, p0_low])
336 faces[face_id] = np.array([p0, p1, p1_low])
340 p2_low = p2 + num_vertices
341 p3_low = p3 + num_vertices
343 faces[face_id] = np.array([p3, p3_low, p2_low])
345 faces[face_id] = np.array([p3, p2_low, p2])
349 p0_low = p0 + num_vertices
350 p3_low = p3 + num_vertices
352 faces[face_id] = np.array([p0, p3_low, p3])
354 faces[face_id] = np.array([p0, p0_low, p3_low])
358 p1_low = p1 + num_vertices
359 p2_low = p2 + num_vertices
361 faces[face_id] = np.array([p1, p2_low, p2])
363 faces[face_id] = np.array([p1, p1_low, p2_low])
369 p2 = 2 * num_vertices - 1
372 faces[face_id] = np.array([p0, p1, p2])
374 faces[face_id] = np.array([p0, p2, p3])
377 elif isinstance(mesh, (hppfcl.Convex, hppfcl.BVHModelBase)):
378 if isinstance(mesh, hppfcl.BVHModelBase):
379 num_vertices = mesh.num_vertices
380 num_tris = mesh.num_tris
382 call_triangles = mesh.tri_indices
383 call_vertices = mesh.vertices
385 elif isinstance(mesh, hppfcl.Convex):
386 num_vertices = mesh.num_points
387 num_tris = mesh.num_polygons
389 call_triangles = mesh.polygons
390 call_vertices = mesh.points
392 faces = np.empty((num_tris, 3), dtype=int)
393 for k
in range(num_tris):
394 tri = call_triangles(k)
395 faces[k] = [tri[i]
for i
in range(3)]
397 vertices = call_vertices()
398 vertices = vertices.astype(np.float32)
401 mesh = mg.TriangularMeshGeometry(vertices, faces)
405 vertices.T, color=np.repeat(np.ones((3, 1)), num_vertices, axis=1)
407 mg.PointsMaterial(size=0.002),
414 raise NotImplementedError(
"loadMesh need hppfcl")
418 import meshcat.geometry
as mg
423 [1.0, 0.0, 0.0, 0.0],
424 [0.0, 0.0, -1.0, 0.0],
425 [0.0, 1.0, 0.0, 0.0],
426 [0.0, 0.0, 0.0, 1.0],
429 RotatedCylinder =
type(
430 "RotatedCylinder", (mg.Cylinder,), {
"intrinsic_transform":
lambda self: R}
433 geom = geometry_object.geometry
435 if WITH_HPP_FCL_BINDINGS
and isinstance(geom, hppfcl.ShapeBase):
436 if isinstance(geom, hppfcl.Capsule):
437 if hasattr(mg,
"TriangularMeshGeometry"):
440 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
441 elif isinstance(geom, hppfcl.Cylinder):
442 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
443 elif isinstance(geom, hppfcl.Cone):
444 obj = RotatedCylinder(2.0 * geom.halfLength, 0, geom.radius, 0)
445 elif isinstance(geom, hppfcl.Box):
446 obj = mg.Box(
npToTuple(2.0 * geom.halfSide))
447 elif isinstance(geom, hppfcl.Sphere):
448 obj = mg.Sphere(geom.radius)
449 elif isinstance(geom, hppfcl.ConvexBase):
453 msg =
"Unsupported geometry type for %s (%s)" % (
454 geometry_object.name,
457 warnings.warn(msg, category=UserWarning, stacklevel=2)
463 nbv = np.array([
max(radial_resolution, 4),
max(cap_resolution, 4)])
467 vertices = np.zeros((nbv[0] * (2 * nbv[1]) + 2, 3))
468 for j
in range(nbv[0]):
469 phi = (2 * np.pi * j) / nbv[0]
470 for i
in range(nbv[1]):
471 theta = (np.pi / 2 * i) / nbv[1]
472 vertices[position + i, :] = np.array(
474 np.cos(theta) * np.cos(phi) * r,
475 np.cos(theta) * np.sin(phi) * r,
476 -h / 2 - np.sin(theta) * r,
479 vertices[position + i + nbv[1], :] = np.array(
481 np.cos(theta) * np.cos(phi) * r,
482 np.cos(theta) * np.sin(phi) * r,
483 h / 2 + np.sin(theta) * r,
486 position += nbv[1] * 2
487 vertices[-2, :] = np.array([0, 0, -h / 2 - r])
488 vertices[-1, :] = np.array([0, 0, h / 2 + r])
489 indexes = np.zeros((nbv[0] * (4 * (nbv[1] - 1) + 4), 3))
492 last = nbv[0] * (2 * nbv[1]) + 1
493 for j
in range(nbv[0]):
494 j_next = (j + 1) % nbv[0]
495 indexes[index + 0] = np.array(
496 [j_next * stride + nbv[1], j_next * stride, j * stride]
498 indexes[index + 1] = np.array(
499 [j * stride + nbv[1], j_next * stride + nbv[1], j * stride]
501 indexes[index + 2] = np.array(
502 [j * stride + nbv[1] - 1, j_next * stride + nbv[1] - 1, last - 1]
504 indexes[index + 3] = np.array(
505 [j_next * stride + 2 * nbv[1] - 1, j * stride + 2 * nbv[1] - 1, last]
507 for i
in range(nbv[1] - 1):
508 indexes[index + 4 + i * 4 + 0] = np.array(
509 [j_next * stride + i, j_next * stride + i + 1, j * stride + i]
511 indexes[index + 4 + i * 4 + 1] = np.array(
512 [j_next * stride + i + 1, j * stride + i + 1, j * stride + i]
514 indexes[index + 4 + i * 4 + 2] = np.array(
516 j_next * stride + nbv[1] + i + 1,
517 j_next * stride + nbv[1] + i,
518 j * stride + nbv[1] + i,
521 indexes[index + 4 + i * 4 + 3] = np.array(
523 j_next * stride + nbv[1] + i + 1,
524 j * stride + nbv[1] + i,
525 j * stride + nbv[1] + i + 1,
528 index += 4 * (nbv[1] - 1) + 4
529 return mg.TriangularMeshGeometry(vertices, indexes)
533 """A Pinocchio display using Meshcat"""
536 FRAME_VEL_COLOR = 0x00FF00
542 "preset1": [np.zeros(3), [1.0, 1.0, 1.0]],
543 "preset2": [[0.0, 0.0, 0.6], [0.8, 1.0, 1.2]],
544 "acrobot": [[0.0, 0.1, 0.0], [0.5, 0.0, 0.2]],
545 "cam_ur": [[0.4, 0.6, -0.2], [1.0, 0.4, 1.2]],
546 "cam_ur2": [[0.4, 0.3, 0.0], [0.5, 0.1, 1.4]],
547 "cam_ur3": [[0.4, 0.3, 0.0], [0.6, 1.3, 0.3]],
548 "cam_ur4": [[-1.0, 0.3, 0.0], [1.3, 0.1, 1.2]],
549 "cam_ur5": [[-1.0, 0.3, 0.0], [-0.05, 1.5, 1.2]],
550 "talos": [[0.0, 1.2, 0.0], [1.5, 0.3, 1.5]],
551 "talos2": [[0.0, 1.1, 0.0], [1.2, 0.6, 1.5]],
557 collision_model=
None,
564 if not import_meshcat_succeed:
566 "Error while importing the viewer client.\n"
567 "Check whether meshcat is properly installed (pip install --user meshcat)."
569 raise ImportError(msg)
583 """Return the name of the geometry object inside the viewer."""
584 if geometry_type
is pin.GeometryType.VISUAL:
586 elif geometry_type
is pin.GeometryType.COLLISION:
589 def initViewer(self, viewer=None, open=False, loadModel=False, zmq_url=None):
590 """Start a new MeshCat server and client.
591 Note: the server can also be started separately using the "meshcat-server" command in a terminal:
592 this enables the server to remain active after the current script ends.
595 self.
viewer = meshcat.Visualizer(zmq_url)
if viewer
is None else viewer
622 """Set the background."""
623 if col_top
is not None:
627 assert preset_name
in COLOR_PRESETS.keys()
628 col_top, col_bot = COLOR_PRESETS[preset_name]
633 self.
viewer.set_cam_target(target)
636 self.
viewer.set_cam_pos(position)
639 """Set the camera angle and position using a given preset."""
647 elt.set_property(
"zoom", zoom)
659 import meshcat.geometry
as mg
662 basic_three_js_transform = np.array(
664 [1.0, 0.0, 0.0, 0.0],
665 [0.0, 0.0, -1.0, 0.0],
666 [0.0, 1.0, 0.0, 0.0],
667 [0.0, 0.0, 0.0, 1.0],
670 RotatedCylinder =
type(
673 {
"intrinsic_transform":
lambda self: basic_three_js_transform},
678 geom = geometry_object.geometry
680 if WITH_HPP_FCL_BINDINGS
and isinstance(geom, hppfcl.ShapeBase):
681 if isinstance(geom, hppfcl.Capsule):
682 if hasattr(mg,
"TriangularMeshGeometry"):
685 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
686 elif isinstance(geom, hppfcl.Cylinder):
687 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
688 elif isinstance(geom, hppfcl.Cone):
689 obj = RotatedCylinder(2.0 * geom.halfLength, 0, geom.radius, 0)
690 elif isinstance(geom, hppfcl.Box):
691 obj = mg.Box(
npToTuple(2.0 * geom.halfSide))
692 elif isinstance(geom, hppfcl.Sphere):
693 obj = mg.Sphere(geom.radius)
694 elif isinstance(geom, hppfcl.Plane):
696 To[:3, 3] = geom.d * geom.n
697 TranslatedPlane =
type(
700 {
"intrinsic_transform":
lambda self: To},
702 sx = geometry_object.meshScale[0] * 10
703 sy = geometry_object.meshScale[1] * 10
704 obj = TranslatedPlane(sx, sy)
705 elif isinstance(geom, hppfcl.Ellipsoid):
706 obj = mg.Ellipsoid(geom.radii)
707 elif isinstance(geom, (hppfcl.Plane, hppfcl.Halfspace)):
708 plane_transform: pin.SE3 = pin.SE3.Identity()
710 plane_transform.rotation = pin.Quaternion.FromTwoVectors(
713 TransformedPlane =
type(
716 {
"intrinsic_transform":
lambda self: plane_transform.homogeneous},
718 obj = TransformedPlane(1000, 1000)
719 elif isinstance(geom, hppfcl.ConvexBase):
723 msg =
"Unsupported geometry type for %s (%s)" % (
724 geometry_object.name,
727 warnings.warn(msg, category=UserWarning, stacklevel=2)
734 if geometry_object.meshPath ==
"":
735 msg =
"Display of geometric primitives is supported only if pinocchio is build with HPP-FCL bindings."
736 warnings.warn(msg, category=UserWarning, stacklevel=2)
740 _, file_extension = os.path.splitext(geometry_object.meshPath)
741 if file_extension.lower() ==
".dae":
743 elif file_extension.lower() ==
".obj":
744 obj = mg.ObjMeshGeometry.from_file(geometry_object.meshPath)
745 elif file_extension.lower() ==
".stl":
746 obj = mg.StlMeshGeometry.from_file(geometry_object.meshPath)
748 msg =
"Unknown mesh file format: {}.".format(geometry_object.meshPath)
749 warnings.warn(msg, category=UserWarning, stacklevel=2)
755 """Load a single geometry object"""
757 meshcat_node = self.
viewer[node_name]
762 if WITH_HPP_FCL_BINDINGS:
763 if isinstance(geometry_object.geometry, hppfcl.ShapeBase):
766 tuple(map(int, hppfcl.__version__.split(
"."))) >= (3, 0, 0)
767 and hppfcl.WITH_OCTOMAP
768 and isinstance(geometry_object.geometry, hppfcl.OcTree)
775 geometry_object.geometry,
778 hppfcl.HeightFieldOBBRSS,
779 hppfcl.HeightFieldAABB,
782 obj =
loadMesh(geometry_object.geometry)
788 "The geometry object named "
789 + geometry_object.name
790 +
" is not supported by Pinocchio/MeshCat for vizualization."
792 warnings.warn(msg, category=UserWarning, stacklevel=2)
794 except Exception
as e:
795 msg =
"Error while loading geometry object: %s\nError message:\n%s" % (
796 geometry_object.name,
799 warnings.warn(msg, category=UserWarning, stacklevel=2)
802 if isinstance(obj, mg.Object):
803 meshcat_node.set_object(obj)
804 elif isinstance(obj, (mg.Geometry, mg.ReferenceSceneElement)):
805 material = mg.MeshPhongMaterial()
808 def to_material_color(rgba) -> int:
809 """Convert rgba color as list into rgba color as int"""
811 int(rgba[0] * 255) * 256**2
812 + int(rgba[1] * 255) * 256
817 meshColor = geometry_object.meshColor
821 material.color = to_material_color(meshColor)
823 if float(meshColor[3]) != 1.0:
824 material.transparent =
True
825 material.opacity = float(meshColor[3])
827 geom_material = geometry_object.meshMaterial
828 if geometry_object.overrideMaterial
and isinstance(
829 geom_material, pin.GeometryPhongMaterial
831 material.emissive = to_material_color(geom_material.meshEmissionColor)
832 material.specular = to_material_color(geom_material.meshSpecularColor)
833 material.shininess = geom_material.meshShininess * 100.0
835 if isinstance(obj, DaeMeshGeometry):
836 obj.path = meshcat_node.path
837 if geometry_object.overrideMaterial:
838 obj.material = material
839 meshcat_node.window.send(obj)
841 meshcat_node.set_object(obj, material)
844 scale = list(np.asarray(geometry_object.meshScale).flatten())
845 meshcat_node.set_property(
"scale", scale)
848 """Load the robot in a MeshCat viewer.
850 rootNodeName: name to give to the robot in the viewer
851 color: optional, color to give to the robot. This overwrites the color present in the urdf.
852 Format is a list of four RGBA floats (between 0 and 1)
861 if self.collision_model
is not None:
862 for collision
in self.collision_model.geometryObjects:
864 collision, pin.GeometryType.COLLISION, color
870 if self.visual_model
is not None:
871 for visual
in self.visual_model.geometryObjects:
879 def reload(self, new_geometry_object, geometry_type=None):
880 """Reload a geometry_object given by its name and its type"""
881 if geometry_type == pin.GeometryType.VISUAL:
882 geom_model = self.visual_model
884 geom_model = self.collision_model
885 geometry_type = pin.GeometryType.COLLISION
887 geom_id = geom_model.getGeometryId(new_geometry_object.name)
888 geom_model.geometryObjects[geom_id] = new_geometry_object
890 self.
delete(new_geometry_object, geometry_type)
891 visual = geom_model.geometryObjects[geom_id]
897 def delete(self, geometry_object, geometry_type):
902 """Display the robot at configuration q in the viewer by placing all the bodies."""
904 pin.forwardKinematics(self.model, self.data, q)
916 if geometry_type == pin.GeometryType.VISUAL:
917 geom_model = self.visual_model
918 geom_data = self.visual_data
920 geom_model = self.collision_model
921 geom_data = self.collision_data
923 pin.updateGeometryPlacements(self.model, self.data, geom_model, geom_data)
924 for visual
in geom_model.geometryObjects:
927 M = geom_data.oMg[geom_model.getGeometryId(visual.name)]
929 geom = visual.geometry
930 if WITH_HPP_FCL_BINDINGS
and isinstance(
931 geom, (hppfcl.Plane, hppfcl.Halfspace)
934 T.translation += M.rotation @ (geom.d * geom.n)
940 self.
viewer[visual_name].set_transform(T)
944 M: pin.SE3 = visual.placement
946 self.
viewer[visual_name].set_transform(T)
949 """Add a visual GeometryObject to the viewer, with an optional color."""
954 if not hasattr(self.
viewer,
"get_image"):
956 "meshcat.Visualizer does not have the get_image() method."
957 " You need meshcat >= 0.2.0 to get this feature."
961 """Capture an image from the Meshcat viewer and return an RGB array."""
962 if w
is not None or h
is not None:
964 img = self.
viewer.get_image(w, h)
966 img = self.
viewer.get_image()
967 img_arr = np.asarray(img)
971 """Set whether to display collision objects or not."""
972 if self.collision_model
is None:
982 """Set whether to display visual objects or not."""
983 if self.visual_model
is None:
992 def displayFrames(self, visibility, frame_ids=None, axis_length=0.2, axis_width=2):
993 """Set whether to display frames or not."""
1000 """Initializes the frame objects for display."""
1001 import meshcat.geometry
as mg
1006 for fid, frame
in enumerate(self.model.frames):
1007 if frame_ids
is None or fid
in frame_ids:
1009 self.
viewer[frame_viz_name].set_object(
1012 position=axis_length * FRAME_AXIS_POSITIONS,
1013 color=FRAME_AXIS_COLORS,
1015 mg.LineBasicMaterial(
1016 linewidth=axis_width,
1025 Updates the frame visualizations with the latest transforms from model data.
1027 pin.updateFramePlacements(self.model, self.data)
1029 frame_name = self.model.frames[fid].name
1031 self.
viewer[frame_viz_name].set_transform(self.data.oMf[fid].homogeneous)
1034 pin.updateFramePlacement(self.model, self.data, frame_id)
1035 vFr = pin.getFrameVelocity(
1036 self.model, self.data, frame_id, pin.LOCAL_WORLD_ALIGNED
1038 line_group_name =
"ee_vel/{}".format(frame_id)
1040 [v_scale * vFr.linear], [frame_id], [line_group_name], [color]
1045 vecs: List[np.ndarray],
1046 frame_ids: List[int],
1047 vec_names: List[str],
1050 """Draw vectors extending from given frames."""
1051 import meshcat.geometry
as mg
1053 if len(vecs) != len(frame_ids)
or len(vecs) != len(vec_names):
1055 "Number of vectors and frames IDs or names is inconsistent."
1057 for i, (fid, v)
in enumerate(zip(frame_ids, vecs)):
1058 frame_pos = self.data.oMf[fid].translation
1059 vertices = np.array([frame_pos, frame_pos + v]).astype(np.float32).T
1061 geometry = mg.PointsGeometry(position=vertices)
1062 geom_object = mg.LineSegments(
1063 geometry, mg.LineBasicMaterial(color=colors[i])
1066 self.
viewer[prefix].set_object(geom_object)
1069 __all__ = [
"MeshcatVisualizer"]