3 from pathlib
import Path
4 from typing
import ClassVar, List
8 from ..
import pinocchio_pywrap_default
as pin
9 from ..deprecation
import DeprecatedWarning
10 from ..utils
import npToTuple
11 from .
import BaseVisualizer
15 import meshcat.geometry
as mg
17 import_meshcat_succeed =
False
19 import_meshcat_succeed =
True
24 import xml.etree.ElementTree
as Et
25 from typing
import Any, Dict, Optional, Set, Union
27 MsgType = Dict[str, Union[str, bytes, bool, float,
"MsgType"]]
32 WITH_HPP_FCL_BINDINGS =
True
34 WITH_HPP_FCL_BINDINGS =
False
36 DEFAULT_COLOR_PROFILES = {
37 "gray": ([0.98, 0.98, 0.98], [0.8, 0.8, 0.8]),
38 "white": ([1.0, 1.0, 1.0], [1.0, 1.0, 1.0]),
40 COLOR_PRESETS = DEFAULT_COLOR_PROFILES.copy()
42 FRAME_AXIS_POSITIONS = (
43 np.array([[0, 0, 0], [1, 0, 0], [0, 0, 0], [0, 1, 0], [0, 0, 0], [0, 0, 1]])
48 np.array([[1, 0, 0], [1, 0.6, 0], [0, 1, 0], [0.6, 1, 0], [0, 0, 1], [0, 0.6, 1]])
55 assert color
is not None
56 color = np.asarray(color)
57 assert color.shape == (3,)
58 return color.clip(0.0, 1.0)
62 """Check whether the geometry object contains a Mesh supported by MeshCat"""
63 if geometry_object.meshPath ==
"":
66 file_extension = Path(geometry_object.meshPath).suffix
67 if file_extension.lower()
in [
".dae",
".obj",
".stl"]:
73 if import_meshcat_succeed:
76 """A cone of the given height and radius. By Three.js convention, the axis
77 of rotational symmetry is aligned with the y-axis.
84 radialSegments: float = 32,
85 openEnded: bool =
False,
93 def lower(self, object_data: Any) -> MsgType:
96 "type":
"ConeGeometry",
104 def __init__(self, dae_path: str, cache: Optional[Set[str]] =
None) ->
None:
105 """Load Collada files with texture images.
107 https://gist.github.com/danzimmerman/a392f8eadcf1166eb5bd80e3922dbdc5
112 dae_path = Path(dae_path)
120 dae_dir = dae_path.parent
121 with dae_path.open()
as text_file:
125 img_resource_paths = []
126 img_lib_element = Et.parse(dae_path).find(
127 "{http://www.collada.org/2005/11/COLLADASchema}library_images"
130 img_resource_paths = [
131 e.text
for e
in img_lib_element.iter()
if e.tag.count(
"init_from")
136 for img_path
in img_resource_paths:
138 if cache
is not None:
139 if img_path
in cache:
145 img_path_abs = img_path
146 if not img_path.is_absolute():
147 img_path_abs = os.path.normpath(dae_dir / img_path_abs)
148 if not img_path_abs.is_file():
149 raise UserWarning(f
"Texture '{img_path}' not found.")
150 with Path(img_path_abs).
open(
"rb")
as img_file:
151 img_data = base64.b64encode(img_file.read())
152 img_uri = f
"data:image/png;base64,{img_data.decode('utf-8')}"
156 """Pack data into a dictionary of the format that must be passed to
157 `Visualizer.window.send`.
160 "type":
"set_object",
163 "metadata": {
"version": 4.5,
"type":
"Object"},
168 "type":
"_meshfile_object",
186 """A plane of the given width and height."""
192 widthSegments: float = 1,
193 heightSegments: float = 1,
201 def lower(self, object_data: Any) -> MsgType:
204 "type":
"PlaneGeometry",
213 WITH_HPP_FCL_BINDINGS
214 and tuple(map(int, hppfcl.__version__.split(
"."))) >= (3, 0, 0)
215 and hppfcl.WITH_OCTOMAP
219 boxes = octree.toBoxes()
223 bs = boxes[0][3] / 2.0
224 num_boxes = len(boxes)
226 box_corners = np.array(
239 all_points = np.empty((8 * num_boxes, 3))
240 all_faces = np.empty((12 * num_boxes, 3), dtype=int)
242 for box_id, box_properties
in enumerate(boxes):
243 box_center = box_properties[:3]
245 corners = box_corners + box_center
246 point_range = range(box_id * 8, (box_id + 1) * 8)
247 all_points[point_range, :] = corners
258 all_faces[face_id] = np.array([C, D, B])
259 all_faces[face_id + 1] = np.array([B, A, C])
260 all_faces[face_id + 2] = np.array([A, B, F])
261 all_faces[face_id + 3] = np.array([F, E, A])
262 all_faces[face_id + 4] = np.array([E, F, H])
263 all_faces[face_id + 5] = np.array([H, G, E])
264 all_faces[face_id + 6] = np.array([G, H, D])
265 all_faces[face_id + 7] = np.array([D, C, G])
267 all_faces[face_id + 8] = np.array([A, E, G])
268 all_faces[face_id + 9] = np.array([G, C, A])
270 all_faces[face_id + 10] = np.array([B, H, F])
271 all_faces[face_id + 11] = np.array([H, B, D])
275 colors = np.empty((all_points.shape[0], 3))
276 colors[:] = np.ones(3)
277 mesh = mg.TriangularMeshGeometry(all_points, all_faces, colors)
283 raise NotImplementedError(
"loadOctree need hppfcl with octomap support")
286 if WITH_HPP_FCL_BINDINGS:
289 if isinstance(mesh, (hppfcl.HeightFieldOBBRSS, hppfcl.HeightFieldAABB)):
290 heights = mesh.getHeights()
291 x_grid = mesh.getXGrid()
292 y_grid = mesh.getYGrid()
293 min_height = mesh.getMinHeight()
295 X, Y = np.meshgrid(x_grid, y_grid)
300 num_cells = (nx) * (ny) * 2 + (nx + ny) * 4 + 2
302 num_vertices = X.size
305 faces = np.empty((num_tris, 3), dtype=int)
306 vertices = np.vstack(
310 X.reshape(num_vertices),
311 Y.reshape(num_vertices),
312 heights.reshape(num_vertices),
318 X.reshape(num_vertices),
319 Y.reshape(num_vertices),
320 np.full(num_vertices, min_height),
328 for y_id
in range(ny):
329 for x_id
in range(nx):
330 p0 = x_id + y_id * (nx + 1)
335 faces[face_id] = np.array([p0, p3, p1])
337 faces[face_id] = np.array([p3, p2, p1])
341 p0_low = p0 + num_vertices
342 p1_low = p1 + num_vertices
344 faces[face_id] = np.array([p0, p1_low, p0_low])
346 faces[face_id] = np.array([p0, p1, p1_low])
350 p2_low = p2 + num_vertices
351 p3_low = p3 + num_vertices
353 faces[face_id] = np.array([p3, p3_low, p2_low])
355 faces[face_id] = np.array([p3, p2_low, p2])
359 p0_low = p0 + num_vertices
360 p3_low = p3 + num_vertices
362 faces[face_id] = np.array([p0, p3_low, p3])
364 faces[face_id] = np.array([p0, p0_low, p3_low])
368 p1_low = p1 + num_vertices
369 p2_low = p2 + num_vertices
371 faces[face_id] = np.array([p1, p2_low, p2])
373 faces[face_id] = np.array([p1, p1_low, p2_low])
379 p2 = 2 * num_vertices - 1
382 faces[face_id] = np.array([p0, p1, p2])
384 faces[face_id] = np.array([p0, p2, p3])
387 elif isinstance(mesh, (hppfcl.Convex, hppfcl.BVHModelBase)):
388 if isinstance(mesh, hppfcl.BVHModelBase):
389 num_vertices = mesh.num_vertices
390 num_tris = mesh.num_tris
392 call_triangles = mesh.tri_indices
393 call_vertices = mesh.vertices
395 elif isinstance(mesh, hppfcl.Convex):
396 num_vertices = mesh.num_points
397 num_tris = mesh.num_polygons
399 call_triangles = mesh.polygons
400 call_vertices = mesh.points
402 faces = np.empty((num_tris, 3), dtype=int)
403 for k
in range(num_tris):
404 tri = call_triangles(k)
405 faces[k] = [tri[i]
for i
in range(3)]
407 vertices = call_vertices()
408 vertices = vertices.astype(np.float32)
411 mesh = mg.TriangularMeshGeometry(vertices, faces)
415 vertices.T, color=np.repeat(np.ones((3, 1)), num_vertices, axis=1)
417 mg.PointsMaterial(size=0.002),
425 raise NotImplementedError(
"loadMesh need hppfcl")
429 import meshcat.geometry
as mg
434 [1.0, 0.0, 0.0, 0.0],
435 [0.0, 0.0, -1.0, 0.0],
436 [0.0, 1.0, 0.0, 0.0],
437 [0.0, 0.0, 0.0, 1.0],
440 RotatedCylinder =
type(
441 "RotatedCylinder", (mg.Cylinder,), {
"intrinsic_transform":
lambda self: R}
444 geom = geometry_object.geometry
446 if WITH_HPP_FCL_BINDINGS
and isinstance(geom, hppfcl.ShapeBase):
447 if isinstance(geom, hppfcl.Capsule):
448 if hasattr(mg,
"TriangularMeshGeometry"):
451 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
452 elif isinstance(geom, hppfcl.Cylinder):
453 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
454 elif isinstance(geom, hppfcl.Cone):
455 obj = RotatedCylinder(2.0 * geom.halfLength, 0, geom.radius, 0)
456 elif isinstance(geom, hppfcl.Box):
457 obj = mg.Box(
npToTuple(2.0 * geom.halfSide))
458 elif isinstance(geom, hppfcl.Sphere):
459 obj = mg.Sphere(geom.radius)
460 elif isinstance(geom, hppfcl.ConvexBase):
464 msg = f
"Unsupported geometry type for {geometry_object.name} ({type(geom)})"
465 warnings.warn(msg, category=UserWarning, stacklevel=2)
471 nbv = np.array([
max(radial_resolution, 4),
max(cap_resolution, 4)])
475 vertices = np.zeros((nbv[0] * (2 * nbv[1]) + 2, 3))
476 for j
in range(nbv[0]):
477 phi = (2 * np.pi * j) / nbv[0]
478 for i
in range(nbv[1]):
479 theta = (np.pi / 2 * i) / nbv[1]
480 vertices[position + i, :] = np.array(
482 np.cos(theta) * np.cos(phi) * r,
483 np.cos(theta) * np.sin(phi) * r,
484 -h / 2 - np.sin(theta) * r,
487 vertices[position + i + nbv[1], :] = np.array(
489 np.cos(theta) * np.cos(phi) * r,
490 np.cos(theta) * np.sin(phi) * r,
491 h / 2 + np.sin(theta) * r,
494 position += nbv[1] * 2
495 vertices[-2, :] = np.array([0, 0, -h / 2 - r])
496 vertices[-1, :] = np.array([0, 0, h / 2 + r])
497 indexes = np.zeros((nbv[0] * (4 * (nbv[1] - 1) + 4), 3))
500 last = nbv[0] * (2 * nbv[1]) + 1
501 for j
in range(nbv[0]):
502 j_next = (j + 1) % nbv[0]
503 indexes[index + 0] = np.array(
504 [j_next * stride + nbv[1], j_next * stride, j * stride]
506 indexes[index + 1] = np.array(
507 [j * stride + nbv[1], j_next * stride + nbv[1], j * stride]
509 indexes[index + 2] = np.array(
510 [j * stride + nbv[1] - 1, j_next * stride + nbv[1] - 1, last - 1]
512 indexes[index + 3] = np.array(
513 [j_next * stride + 2 * nbv[1] - 1, j * stride + 2 * nbv[1] - 1, last]
515 for i
in range(nbv[1] - 1):
516 indexes[index + 4 + i * 4 + 0] = np.array(
517 [j_next * stride + i, j_next * stride + i + 1, j * stride + i]
519 indexes[index + 4 + i * 4 + 1] = np.array(
520 [j_next * stride + i + 1, j * stride + i + 1, j * stride + i]
522 indexes[index + 4 + i * 4 + 2] = np.array(
524 j_next * stride + nbv[1] + i + 1,
525 j_next * stride + nbv[1] + i,
526 j * stride + nbv[1] + i,
529 indexes[index + 4 + i * 4 + 3] = np.array(
531 j_next * stride + nbv[1] + i + 1,
532 j * stride + nbv[1] + i,
533 j * stride + nbv[1] + i + 1,
536 index += 4 * (nbv[1] - 1) + 4
537 return mg.TriangularMeshGeometry(vertices, indexes)
541 """A Pinocchio display using Meshcat"""
544 FRAME_VEL_COLOR = 0x00FF00
545 CAMERA_PRESETS: ClassVar = {
550 "preset1": [np.zeros(3), [1.0, 1.0, 1.0]],
551 "preset2": [[0.0, 0.0, 0.6], [0.8, 1.0, 1.2]],
552 "acrobot": [[0.0, 0.1, 0.0], [0.5, 0.0, 0.2]],
553 "cam_ur": [[0.4, 0.6, -0.2], [1.0, 0.4, 1.2]],
554 "cam_ur2": [[0.4, 0.3, 0.0], [0.5, 0.1, 1.4]],
555 "cam_ur3": [[0.4, 0.3, 0.0], [0.6, 1.3, 0.3]],
556 "cam_ur4": [[-1.0, 0.3, 0.0], [1.3, 0.1, 1.2]],
557 "cam_ur5": [[-1.0, 0.3, 0.0], [-0.05, 1.5, 1.2]],
558 "talos": [[0.0, 1.2, 0.0], [1.5, 0.3, 1.5]],
559 "talos2": [[0.0, 1.1, 0.0], [1.2, 0.6, 1.5]],
565 collision_model=
None,
572 if not import_meshcat_succeed:
574 "Error while importing the viewer client.\n"
575 "Check whether meshcat is properly installed "
576 "(pip install --user meshcat)."
578 raise ImportError(msg)
592 """Return the name of the geometry object inside the viewer."""
593 if geometry_type
is pin.GeometryType.VISUAL:
595 elif geometry_type
is pin.GeometryType.COLLISION:
598 def initViewer(self, viewer=None, open=False, loadModel=False, zmq_url=None):
599 """Start a new MeshCat server and client.
600 Note: the server can also be started separately using the "meshcat-server"
601 command in a terminal:
602 this enables the server to remain active after the current script ends.
605 self.
viewer = meshcat.Visualizer(zmq_url)
if viewer
is None else viewer
632 """Set the background."""
633 if col_top
is not None:
637 assert preset_name
in COLOR_PRESETS.keys()
638 col_top, col_bot = COLOR_PRESETS[preset_name]
643 self.
viewer.set_cam_target(target)
646 self.
viewer.set_cam_pos(position)
649 """Set the camera angle and position using a given preset."""
650 assert preset_key
in self.CAMERA_PRESETS
651 cam_val = self.CAMERA_PRESETS[preset_key]
657 elt.set_property(
"zoom", zoom)
669 import meshcat.geometry
as mg
672 basic_three_js_transform = np.array(
674 [1.0, 0.0, 0.0, 0.0],
675 [0.0, 0.0, -1.0, 0.0],
676 [0.0, 1.0, 0.0, 0.0],
677 [0.0, 0.0, 0.0, 1.0],
680 RotatedCylinder =
type(
683 {
"intrinsic_transform":
lambda self: basic_three_js_transform},
688 geom = geometry_object.geometry
690 if WITH_HPP_FCL_BINDINGS
and isinstance(geom, hppfcl.ShapeBase):
691 if isinstance(geom, hppfcl.Capsule):
692 if hasattr(mg,
"TriangularMeshGeometry"):
695 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
696 elif isinstance(geom, hppfcl.Cylinder):
697 obj = RotatedCylinder(2.0 * geom.halfLength, geom.radius)
698 elif isinstance(geom, hppfcl.Cone):
699 obj = RotatedCylinder(2.0 * geom.halfLength, 0, geom.radius, 0)
700 elif isinstance(geom, hppfcl.Box):
701 obj = mg.Box(
npToTuple(2.0 * geom.halfSide))
702 elif isinstance(geom, hppfcl.Sphere):
703 obj = mg.Sphere(geom.radius)
704 elif isinstance(geom, hppfcl.Plane):
706 To[:3, 3] = geom.d * geom.n
707 TranslatedPlane =
type(
710 {
"intrinsic_transform":
lambda self: To},
712 sx = geometry_object.meshScale[0] * 10
713 sy = geometry_object.meshScale[1] * 10
714 obj = TranslatedPlane(sx, sy)
715 elif isinstance(geom, hppfcl.Ellipsoid):
716 obj = mg.Ellipsoid(geom.radii)
717 elif isinstance(geom, (hppfcl.Plane, hppfcl.Halfspace)):
718 plane_transform: pin.SE3 = pin.SE3.Identity()
720 plane_transform.rotation = pin.Quaternion.FromTwoVectors(
723 TransformedPlane =
type(
726 {
"intrinsic_transform":
lambda self: plane_transform.homogeneous},
728 obj = TransformedPlane(1000, 1000)
729 elif isinstance(geom, hppfcl.ConvexBase):
733 msg = f
"Unsupported geometry type for {geometry_object.name} ({type(geom)})"
734 warnings.warn(msg, category=UserWarning, stacklevel=2)
741 if geometry_object.meshPath ==
"":
743 "Display of geometric primitives is supported only if "
744 "pinocchio is build with HPP-FCL bindings."
746 warnings.warn(msg, category=UserWarning, stacklevel=2)
750 file_extension = Path(geometry_object.meshPath).suffix
751 if file_extension.lower() ==
".dae":
753 elif file_extension.lower() ==
".obj":
754 obj = mg.ObjMeshGeometry.from_file(geometry_object.meshPath)
755 elif file_extension.lower() ==
".stl":
756 obj = mg.StlMeshGeometry.from_file(geometry_object.meshPath)
758 msg = f
"Unknown mesh file format: {geometry_object.meshPath}."
759 warnings.warn(msg, category=UserWarning, stacklevel=2)
765 """Load a single geometry object"""
767 meshcat_node = self.
viewer[node_name]
772 if WITH_HPP_FCL_BINDINGS:
773 if isinstance(geometry_object.geometry, hppfcl.ShapeBase):
776 tuple(map(int, hppfcl.__version__.split(
"."))) >= (3, 0, 0)
777 and hppfcl.WITH_OCTOMAP
778 and isinstance(geometry_object.geometry, hppfcl.OcTree)
785 geometry_object.geometry,
788 hppfcl.HeightFieldOBBRSS,
789 hppfcl.HeightFieldAABB,
792 obj =
loadMesh(geometry_object.geometry)
798 "The geometry object named "
799 + geometry_object.name
800 +
" is not supported by Pinocchio/MeshCat for vizualization."
802 warnings.warn(msg, category=UserWarning, stacklevel=2)
804 except Exception
as e:
806 "Error while loading geometry object: "
807 f
"{geometry_object.name}\nError message:\n{e}"
809 warnings.warn(msg, category=UserWarning, stacklevel=2)
812 if isinstance(obj, mg.Object):
813 meshcat_node.set_object(obj)
814 elif isinstance(obj, (mg.Geometry, mg.ReferenceSceneElement)):
815 material = mg.MeshPhongMaterial()
819 def to_material_color(rgba) -> int:
820 """Convert rgba color as list into rgba color as int"""
822 int(rgba[0] * 255) * 256**2
823 + int(rgba[1] * 255) * 256
828 meshColor = geometry_object.meshColor
832 material.color = to_material_color(meshColor)
834 if float(meshColor[3]) != 1.0:
835 material.transparent =
True
836 material.opacity = float(meshColor[3])
838 geom_material = geometry_object.meshMaterial
839 if geometry_object.overrideMaterial
and isinstance(
840 geom_material, pin.GeometryPhongMaterial
842 material.emissive = to_material_color(geom_material.meshEmissionColor)
843 material.specular = to_material_color(geom_material.meshSpecularColor)
844 material.shininess = geom_material.meshShininess * 100.0
846 if isinstance(obj, DaeMeshGeometry):
847 obj.path = meshcat_node.path
848 scale = list(np.asarray(geometry_object.meshScale).flatten())
850 if geometry_object.overrideMaterial:
851 obj.material = material
852 meshcat_node.window.send(obj)
854 meshcat_node.set_object(obj, material)
857 if is_mesh
and not isinstance(obj, DaeMeshGeometry):
858 scale = list(np.asarray(geometry_object.meshScale).flatten())
859 meshcat_node.set_property(
"scale", scale)
863 rootNodeName="pinocchio",
865 collision_color=None,
868 """Load the robot in a MeshCat viewer.
870 rootNodeName: name to give to the robot in the viewer
871 color: deprecated and optional, color to give to both the collision
872 and visual models of the robot. This setting overwrites any color
873 specified in the robot description. Format is a list of four
874 RGBA floating-point numbers (between 0 and 1)
875 collision_color: optional, color to give to the collision model of
876 the robot. Format is a list of four RGBA floating-point numbers
878 visual_color: optional, color to give to the visual model of
879 the robot. Format is a list of four RGBA floating-point numbers
882 if color
is not None:
884 "The 'color' argument is deprecated and will be removed in a "
885 "future version of Pinocchio. Consider using "
886 "'collision_color' and 'visual_color' instead.",
887 category=DeprecatedWarning,
889 collision_color = color
898 if self.collision_model
is not None:
899 for collision
in self.collision_model.geometryObjects:
901 collision, pin.GeometryType.COLLISION, collision_color
907 if self.visual_model
is not None:
908 for visual
in self.visual_model.geometryObjects:
910 visual, pin.GeometryType.VISUAL, visual_color
918 def reload(self, new_geometry_object, geometry_type=None):
919 """Reload a geometry_object given by its name and its type"""
920 if geometry_type == pin.GeometryType.VISUAL:
921 geom_model = self.visual_model
923 geom_model = self.collision_model
924 geometry_type = pin.GeometryType.COLLISION
926 geom_id = geom_model.getGeometryId(new_geometry_object.name)
927 geom_model.geometryObjects[geom_id] = new_geometry_object
929 self.
delete(new_geometry_object, geometry_type)
930 visual = geom_model.geometryObjects[geom_id]
936 def delete(self, geometry_object, geometry_type):
942 Display the robot at configuration q in the viewer by placing all the bodies
945 pin.forwardKinematics(self.model, self.data, q)
957 if geometry_type == pin.GeometryType.VISUAL:
958 geom_model = self.visual_model
959 geom_data = self.visual_data
961 geom_model = self.collision_model
962 geom_data = self.collision_data
964 pin.updateGeometryPlacements(self.model, self.data, geom_model, geom_data)
965 for visual
in geom_model.geometryObjects:
968 M = geom_data.oMg[geom_model.getGeometryId(visual.name)]
971 geom = visual.geometry
972 if WITH_HPP_FCL_BINDINGS
and isinstance(
973 geom, (hppfcl.Plane, hppfcl.Halfspace)
976 T.translation += M.rotation @ (geom.d * geom.n)
982 self.
viewer[visual_name].set_transform(T)
986 M: pin.SE3 = visual.placement
988 self.
viewer[visual_name].set_transform(T)
991 """Add a visual GeometryObject to the viewer, with an optional color."""
996 if not hasattr(self.
viewer,
"get_image"):
998 "meshcat.Visualizer does not have the get_image() method."
999 " You need meshcat >= 0.2.0 to get this feature."
1003 """Capture an image from the Meshcat viewer and return an RGB array."""
1004 if w
is not None or h
is not None:
1006 img = self.
viewer.get_image(w, h)
1008 img = self.
viewer.get_image()
1009 img_arr = np.asarray(img)
1013 """Set whether to display collision objects or not."""
1014 if self.collision_model
is None:
1024 """Set whether to display visual objects or not."""
1025 if self.visual_model
is None:
1034 def displayFrames(self, visibility, frame_ids=None, axis_length=0.2, axis_width=2):
1035 """Set whether to display frames or not."""
1042 """Initializes the frame objects for display."""
1043 import meshcat.geometry
as mg
1048 for fid, frame
in enumerate(self.model.frames):
1049 if frame_ids
is None or fid
in frame_ids:
1050 frame_viz_name = f
"{self.viewerFramesGroupName}/{frame.name}"
1051 self.
viewer[frame_viz_name].set_object(
1054 position=axis_length * FRAME_AXIS_POSITIONS,
1055 color=FRAME_AXIS_COLORS,
1057 mg.LineBasicMaterial(
1058 linewidth=axis_width,
1067 Updates the frame visualizations with the latest transforms from model data.
1069 pin.updateFramePlacements(self.model, self.data)
1071 frame_name = self.model.frames[fid].name
1072 frame_viz_name = f
"{self.viewerFramesGroupName}/{frame_name}"
1073 self.
viewer[frame_viz_name].set_transform(self.data.oMf[fid].homogeneous)
1076 pin.updateFramePlacement(self.model, self.data, frame_id)
1077 vFr = pin.getFrameVelocity(
1078 self.model, self.data, frame_id, pin.LOCAL_WORLD_ALIGNED
1080 line_group_name = f
"ee_vel/{frame_id}"
1082 [v_scale * vFr.linear], [frame_id], [line_group_name], [color]
1087 vecs: List[np.ndarray],
1088 frame_ids: List[int],
1089 vec_names: List[str],
1092 """Draw vectors extending from given frames."""
1093 import meshcat.geometry
as mg
1095 if len(vecs) != len(frame_ids)
or len(vecs) != len(vec_names):
1097 "Number of vectors and frames IDs or names is inconsistent."
1099 for i, (fid, v)
in enumerate(zip(frame_ids, vecs)):
1100 frame_pos = self.data.oMf[fid].translation
1101 vertices = np.array([frame_pos, frame_pos + v]).astype(np.float32).T
1103 geometry = mg.PointsGeometry(position=vertices)
1104 geom_object = mg.LineSegments(
1105 geometry, mg.LineBasicMaterial(color=colors[i])
1108 self.
viewer[prefix].set_object(geom_object)
1111 __all__ = [
"MeshcatVisualizer"]