meshcat_visualizer.py
Go to the documentation of this file.
1 import os
2 import warnings
3 from pathlib import Path
4 from typing import ClassVar, List
5 
6 import numpy as np
7 
8 from .. import pinocchio_pywrap_default as pin
9 from ..deprecation import DeprecatedWarning
10 from ..utils import npToTuple
11 from . import BaseVisualizer
12 
13 try:
14  import meshcat
15  import meshcat.geometry as mg
16 except ImportError:
17  import_meshcat_succeed = False
18 else:
19  import_meshcat_succeed = True
20 
21 import base64
22 
23 # DaeMeshGeometry
24 import xml.etree.ElementTree as Et
25 from typing import Any, Dict, Optional, Set, Union
26 
27 MsgType = Dict[str, Union[str, bytes, bool, float, "MsgType"]]
28 
29 try:
30  import hppfcl
31 
32  WITH_HPP_FCL_BINDINGS = True
33 except ImportError:
34  WITH_HPP_FCL_BINDINGS = False
35 
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]),
39 }
40 COLOR_PRESETS = DEFAULT_COLOR_PROFILES.copy()
41 
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]])
44  .astype(np.float32)
45  .T
46 )
47 FRAME_AXIS_COLORS = (
48  np.array([[1, 0, 0], [1, 0.6, 0], [0, 1, 0], [0.6, 1, 0], [0, 0, 1], [0, 0.6, 1]])
49  .astype(np.float32)
50  .T
51 )
52 
53 
54 def getColor(color):
55  assert color is not None
56  color = np.asarray(color)
57  assert color.shape == (3,)
58  return color.clip(0.0, 1.0)
59 
60 
61 def hasMeshFileInfo(geometry_object):
62  """Check whether the geometry object contains a Mesh supported by MeshCat"""
63  if geometry_object.meshPath == "":
64  return False
65 
66  file_extension = Path(geometry_object.meshPath).suffix
67  if file_extension.lower() in [".dae", ".obj", ".stl"]:
68  return True
69 
70  return False
71 
72 
73 if import_meshcat_succeed:
74  # Code adapted from Jiminy
75  class Cone(mg.Geometry):
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.
78  """
79 
80  def __init__(
81  self,
82  height: float,
83  radius: float,
84  radialSegments: float = 32,
85  openEnded: bool = False,
86  ):
87  super().__init__()
88  self.radius = radius
89  self.height = height
90  self.radialSegments = radialSegments
91  self.openEnded = openEnded
92 
93  def lower(self, object_data: Any) -> MsgType:
94  return {
95  "uuid": self.uuid,
96  "type": "ConeGeometry",
97  "radius": self.radius,
98  "height": self.height,
99  "radialSegments": self.radialSegments,
100  "openEnded": self.openEnded,
101  }
102 
103  class DaeMeshGeometry(mg.ReferenceSceneElement):
104  def __init__(self, dae_path: str, cache: Optional[Set[str]] = None) -> None:
105  """Load Collada files with texture images.
106  Inspired from
107  https://gist.github.com/danzimmerman/a392f8eadcf1166eb5bd80e3922dbdc5
108  """
109  # Init base class
110  super().__init__()
111 
112  dae_path = Path(dae_path)
113 
114  # Attributes to be specified by the user
115  self.path = None
116  self.material = None
117  self.intrinsic_transform = mg.tf.identity_matrix()
118 
119  # Raw file content
120  dae_dir = dae_path.parent
121  with dae_path.open() as text_file:
122  self.dae_raw = text_file.read()
123 
124  # Parse the image resource in Collada file
125  img_resource_paths = []
126  img_lib_element = Et.parse(dae_path).find(
127  "{http://www.collada.org/2005/11/COLLADASchema}library_images"
128  )
129  if img_lib_element:
130  img_resource_paths = [
131  e.text for e in img_lib_element.iter() if e.tag.count("init_from")
132  ]
133 
134  # Convert textures to data URL for Three.js ColladaLoader to load them
135  self.img_resources = {}
136  for img_path in img_resource_paths:
137  # Return empty string if already in cache
138  if cache is not None:
139  if img_path in cache:
140  self.img_resources[img_path] = ""
141  continue
142  cache.add(img_path)
143 
144  # Encode texture in base64
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')}"
153  self.img_resources[img_path] = img_uri
154 
155  def lower(self) -> Dict[str, Any]:
156  """Pack data into a dictionary of the format that must be passed to
157  `Visualizer.window.send`.
158  """
159  data = {
160  "type": "set_object",
161  "path": self.path.lower() if self.path is not None else "",
162  "object": {
163  "metadata": {"version": 4.5, "type": "Object"},
164  "geometries": [],
165  "materials": [],
166  "object": {
167  "uuid": self.uuid,
168  "type": "_meshfile_object",
169  "format": "dae",
170  "data": self.dae_raw,
171  "resources": self.img_resources,
172  "matrix": list(self.intrinsic_transform.flatten()),
173  },
174  },
175  }
176  if self.material is not None:
177  self.material.lower_in_object(data)
178  return data
179 
180  def set_scale(self, scale) -> None:
181  self.intrinsic_transform[:3, :3] = np.diag(scale)
182 
183  # end code adapted from Jiminy
184 
185  class Plane(mg.Geometry):
186  """A plane of the given width and height."""
187 
188  def __init__(
189  self,
190  width: float,
191  height: float,
192  widthSegments: float = 1,
193  heightSegments: float = 1,
194  ):
195  super().__init__()
196  self.width = width
197  self.height = height
198  self.widthSegments = widthSegments
199  self.heightSegments = heightSegments
200 
201  def lower(self, object_data: Any) -> MsgType:
202  return {
203  "uuid": self.uuid,
204  "type": "PlaneGeometry",
205  "width": self.width,
206  "height": self.height,
207  "widthSegments": self.widthSegments,
208  "heightSegments": self.heightSegments,
209  }
210 
211 
212 if (
213  WITH_HPP_FCL_BINDINGS
214  and tuple(map(int, hppfcl.__version__.split("."))) >= (3, 0, 0)
215  and hppfcl.WITH_OCTOMAP
216 ):
217 
218  def loadOctree(octree: hppfcl.OcTree):
219  boxes = octree.toBoxes()
220 
221  if len(boxes) == 0:
222  return
223  bs = boxes[0][3] / 2.0
224  num_boxes = len(boxes)
225 
226  box_corners = np.array(
227  [
228  [bs, bs, bs],
229  [bs, bs, -bs],
230  [bs, -bs, bs],
231  [bs, -bs, -bs],
232  [-bs, bs, bs],
233  [-bs, bs, -bs],
234  [-bs, -bs, bs],
235  [-bs, -bs, -bs],
236  ]
237  )
238 
239  all_points = np.empty((8 * num_boxes, 3))
240  all_faces = np.empty((12 * num_boxes, 3), dtype=int)
241  face_id = 0
242  for box_id, box_properties in enumerate(boxes):
243  box_center = box_properties[:3]
244 
245  corners = box_corners + box_center
246  point_range = range(box_id * 8, (box_id + 1) * 8)
247  all_points[point_range, :] = corners
248 
249  A = box_id * 8
250  B = A + 1
251  C = B + 1
252  D = C + 1
253  E = D + 1
254  F = E + 1
255  G = F + 1
256  H = G + 1
257 
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])
266  # # top
267  all_faces[face_id + 8] = np.array([A, E, G])
268  all_faces[face_id + 9] = np.array([G, C, A])
269  # # bottom
270  all_faces[face_id + 10] = np.array([B, H, F])
271  all_faces[face_id + 11] = np.array([H, B, D])
272 
273  face_id += 12
274 
275  colors = np.empty((all_points.shape[0], 3))
276  colors[:] = np.ones(3)
277  mesh = mg.TriangularMeshGeometry(all_points, all_faces, colors)
278  return mesh
279 
280 else:
281 
282  def loadOctree(octree):
283  raise NotImplementedError("loadOctree need hppfcl with octomap support")
284 
285 
286 if WITH_HPP_FCL_BINDINGS:
287 
288  def loadMesh(mesh):
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()
294 
295  X, Y = np.meshgrid(x_grid, y_grid)
296 
297  nx = len(x_grid) - 1
298  ny = len(y_grid) - 1
299 
300  num_cells = (nx) * (ny) * 2 + (nx + ny) * 4 + 2
301 
302  num_vertices = X.size
303  num_tris = num_cells
304 
305  faces = np.empty((num_tris, 3), dtype=int)
306  vertices = np.vstack(
307  (
308  np.stack(
309  (
310  X.reshape(num_vertices),
311  Y.reshape(num_vertices),
312  heights.reshape(num_vertices),
313  ),
314  axis=1,
315  ),
316  np.stack(
317  (
318  X.reshape(num_vertices),
319  Y.reshape(num_vertices),
320  np.full(num_vertices, min_height),
321  ),
322  axis=1,
323  ),
324  )
325  )
326 
327  face_id = 0
328  for y_id in range(ny):
329  for x_id in range(nx):
330  p0 = x_id + y_id * (nx + 1)
331  p1 = p0 + 1
332  p2 = p1 + nx + 1
333  p3 = p2 - 1
334 
335  faces[face_id] = np.array([p0, p3, p1])
336  face_id += 1
337  faces[face_id] = np.array([p3, p2, p1])
338  face_id += 1
339 
340  if y_id == 0:
341  p0_low = p0 + num_vertices
342  p1_low = p1 + num_vertices
343 
344  faces[face_id] = np.array([p0, p1_low, p0_low])
345  face_id += 1
346  faces[face_id] = np.array([p0, p1, p1_low])
347  face_id += 1
348 
349  if y_id == ny - 1:
350  p2_low = p2 + num_vertices
351  p3_low = p3 + num_vertices
352 
353  faces[face_id] = np.array([p3, p3_low, p2_low])
354  face_id += 1
355  faces[face_id] = np.array([p3, p2_low, p2])
356  face_id += 1
357 
358  if x_id == 0:
359  p0_low = p0 + num_vertices
360  p3_low = p3 + num_vertices
361 
362  faces[face_id] = np.array([p0, p3_low, p3])
363  face_id += 1
364  faces[face_id] = np.array([p0, p0_low, p3_low])
365  face_id += 1
366 
367  if x_id == nx - 1:
368  p1_low = p1 + num_vertices
369  p2_low = p2 + num_vertices
370 
371  faces[face_id] = np.array([p1, p2_low, p2])
372  face_id += 1
373  faces[face_id] = np.array([p1, p1_low, p2_low])
374  face_id += 1
375 
376  # Last face
377  p0 = num_vertices
378  p1 = p0 + nx
379  p2 = 2 * num_vertices - 1
380  p3 = p2 - nx
381 
382  faces[face_id] = np.array([p0, p1, p2])
383  face_id += 1
384  faces[face_id] = np.array([p0, p2, p3])
385  face_id += 1
386 
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
391 
392  call_triangles = mesh.tri_indices
393  call_vertices = mesh.vertices
394 
395  elif isinstance(mesh, hppfcl.Convex):
396  num_vertices = mesh.num_points
397  num_tris = mesh.num_polygons
398 
399  call_triangles = mesh.polygons
400  call_vertices = mesh.points
401 
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)]
406 
407  vertices = call_vertices()
408  vertices = vertices.astype(np.float32)
409 
410  if num_tris > 0:
411  mesh = mg.TriangularMeshGeometry(vertices, faces)
412  else:
413  mesh = mg.Points(
414  mg.PointsGeometry(
415  vertices.T, color=np.repeat(np.ones((3, 1)), num_vertices, axis=1)
416  ),
417  mg.PointsMaterial(size=0.002),
418  )
419 
420  return mesh
421 
422 else:
423 
424  def loadMesh(mesh):
425  raise NotImplementedError("loadMesh need hppfcl")
426 
427 
428 def loadPrimitive(geometry_object):
429  import meshcat.geometry as mg
430 
431  # Cylinders need to be rotated
432  R = np.array(
433  [
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],
438  ]
439  )
440  RotatedCylinder = type(
441  "RotatedCylinder", (mg.Cylinder,), {"intrinsic_transform": lambda self: R}
442  )
443 
444  geom = geometry_object.geometry
445  obj = None
446  if WITH_HPP_FCL_BINDINGS and isinstance(geom, hppfcl.ShapeBase):
447  if isinstance(geom, hppfcl.Capsule):
448  if hasattr(mg, "TriangularMeshGeometry"):
449  obj = createCapsule(2.0 * geom.halfLength, geom.radius)
450  else:
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):
461  obj = loadMesh(geom)
462 
463  if obj is None:
464  msg = f"Unsupported geometry type for {geometry_object.name} ({type(geom)})"
465  warnings.warn(msg, category=UserWarning, stacklevel=2)
466 
467  return obj
468 
469 
470 def createCapsule(length, radius, radial_resolution=30, cap_resolution=10):
471  nbv = np.array([max(radial_resolution, 4), max(cap_resolution, 4)])
472  h = length
473  r = radius
474  position = 0
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(
481  [
482  np.cos(theta) * np.cos(phi) * r,
483  np.cos(theta) * np.sin(phi) * r,
484  -h / 2 - np.sin(theta) * r,
485  ]
486  )
487  vertices[position + i + nbv[1], :] = np.array(
488  [
489  np.cos(theta) * np.cos(phi) * r,
490  np.cos(theta) * np.sin(phi) * r,
491  h / 2 + np.sin(theta) * r,
492  ]
493  )
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))
498  index = 0
499  stride = nbv[1] * 2
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]
505  )
506  indexes[index + 1] = np.array(
507  [j * stride + nbv[1], j_next * stride + nbv[1], j * stride]
508  )
509  indexes[index + 2] = np.array(
510  [j * stride + nbv[1] - 1, j_next * stride + nbv[1] - 1, last - 1]
511  )
512  indexes[index + 3] = np.array(
513  [j_next * stride + 2 * nbv[1] - 1, j * stride + 2 * nbv[1] - 1, last]
514  )
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]
518  )
519  indexes[index + 4 + i * 4 + 1] = np.array(
520  [j_next * stride + i + 1, j * stride + i + 1, j * stride + i]
521  )
522  indexes[index + 4 + i * 4 + 2] = np.array(
523  [
524  j_next * stride + nbv[1] + i + 1,
525  j_next * stride + nbv[1] + i,
526  j * stride + nbv[1] + i,
527  ]
528  )
529  indexes[index + 4 + i * 4 + 3] = np.array(
530  [
531  j_next * stride + nbv[1] + i + 1,
532  j * stride + nbv[1] + i,
533  j * stride + nbv[1] + i + 1,
534  ]
535  )
536  index += 4 * (nbv[1] - 1) + 4
537  return mg.TriangularMeshGeometry(vertices, indexes)
538 
539 
540 class MeshcatVisualizer(BaseVisualizer):
541  """A Pinocchio display using Meshcat"""
542 
543  FORCE_SCALE = 0.06
544  FRAME_VEL_COLOR = 0x00FF00
545  CAMERA_PRESETS: ClassVar = {
546  "preset0": [
547  np.zeros(3), # target
548  [3.0, 0.0, 1.0], # anchor point (x, z, -y) lhs coords
549  ],
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]], # x>0 to x<0
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]],
560  }
561 
562  def __init__(
563  self,
564  model=pin.Model(),
565  collision_model=None,
566  visual_model=None,
567  copy_models=False,
568  data=None,
569  collision_data=None,
570  visual_data=None,
571  ):
572  if not import_meshcat_succeed:
573  msg = (
574  "Error while importing the viewer client.\n"
575  "Check whether meshcat is properly installed "
576  "(pip install --user meshcat)."
577  )
578  raise ImportError(msg)
579 
580  super().__init__(
581  model,
582  collision_model,
583  visual_model,
584  copy_models,
585  data,
586  collision_data,
587  visual_data,
588  )
589  self.static_objects = []
590 
591  def getViewerNodeName(self, geometry_object, geometry_type):
592  """Return the name of the geometry object inside the viewer."""
593  if geometry_type is pin.GeometryType.VISUAL:
594  return self.viewerVisualGroupName + "/" + geometry_object.name
595  elif geometry_type is pin.GeometryType.COLLISION:
596  return self.viewerCollisionGroupName + "/" + geometry_object.name
597 
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.
603  """
604 
605  self.viewer = meshcat.Visualizer(zmq_url) if viewer is None else viewer
606 
607  self._node_default_cam = self.viewer["/Cameras/default"]
608  self._node_background = self.viewer["/Background"]
609  self._rot_cam_key = "rotated/<object>"
610  self.static_objects = []
611 
613 
614  self._node_default_cam = self.viewer["/Cameras/default"]
615  self._node_background = self.viewer["/Background"]
616  self._rot_cam_key = "rotated/object"
617  self.static_objects = []
618 
620 
621  if open:
622  self.viewer.open()
623 
624  if loadModel:
625  self.loadViewerModel()
626 
627  def reset(self):
628  self.viewer.delete()
629  self.static_objects = []
630 
631  def setBackgroundColor(self, preset_name: str = "gray", col_top=None, col_bot=None):
632  """Set the background."""
633  if col_top is not None:
634  if col_bot is None:
635  col_bot = col_top
636  else:
637  assert preset_name in COLOR_PRESETS.keys()
638  col_top, col_bot = COLOR_PRESETS[preset_name]
639  self._node_background.set_property("top_color", col_top)
640  self._node_background.set_property("bottom_color", col_bot)
641 
642  def setCameraTarget(self, target: np.ndarray):
643  self.viewer.set_cam_target(target)
644 
645  def setCameraPosition(self, position: np.ndarray):
646  self.viewer.set_cam_pos(position)
647 
648  def setCameraPreset(self, preset_key: str):
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]
652  self.setCameraTarget(cam_val[0])
653  self.setCameraPosition(cam_val[1])
654 
655  def setCameraZoom(self, zoom: float):
656  elt = self._node_default_cam[self._rot_cam_key]
657  elt.set_property("zoom", zoom)
658 
659  def setCameraPose(self, pose):
660  self._node_default_cam.set_transform(pose)
661 
663  self.setCameraPosition([0, 0, 0])
664 
666  self.setCameraPosition([3, 0, 1])
667 
668  def loadPrimitive(self, geometry_object: pin.GeometryObject):
669  import meshcat.geometry as mg
670 
671  # Cylinders need to be rotated
672  basic_three_js_transform = np.array(
673  [
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],
678  ]
679  )
680  RotatedCylinder = type(
681  "RotatedCylinder",
682  (mg.Cylinder,),
683  {"intrinsic_transform": lambda self: basic_three_js_transform},
684  )
685 
686  # Cones need to be rotated
687 
688  geom = geometry_object.geometry
689  obj = None
690  if WITH_HPP_FCL_BINDINGS and isinstance(geom, hppfcl.ShapeBase):
691  if isinstance(geom, hppfcl.Capsule):
692  if hasattr(mg, "TriangularMeshGeometry"):
693  obj = createCapsule(2.0 * geom.halfLength, geom.radius)
694  else:
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):
705  To = np.eye(4)
706  To[:3, 3] = geom.d * geom.n
707  TranslatedPlane = type(
708  "TranslatedPlane",
709  (mg.Plane,),
710  {"intrinsic_transform": lambda self: To},
711  )
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()
719  # plane_transform.translation[:] = geom.d # Does not work
720  plane_transform.rotation = pin.Quaternion.FromTwoVectors(
721  pin.ZAxis, geom.n
722  ).toRotationMatrix()
723  TransformedPlane = type(
724  "TransformedPlane",
725  (Plane,),
726  {"intrinsic_transform": lambda self: plane_transform.homogeneous},
727  )
728  obj = TransformedPlane(1000, 1000)
729  elif isinstance(geom, hppfcl.ConvexBase):
730  obj = loadMesh(geom)
731 
732  if obj is None:
733  msg = f"Unsupported geometry type for {geometry_object.name} ({type(geom)})"
734  warnings.warn(msg, category=UserWarning, stacklevel=2)
735  obj = None
736 
737  return obj
738 
739  def loadMeshFromFile(self, geometry_object):
740  # Mesh path is empty if Pinocchio is built without HPP-FCL bindings
741  if geometry_object.meshPath == "":
742  msg = (
743  "Display of geometric primitives is supported only if "
744  "pinocchio is build with HPP-FCL bindings."
745  )
746  warnings.warn(msg, category=UserWarning, stacklevel=2)
747  return None
748 
749  # Get file type from filename extension.
750  file_extension = Path(geometry_object.meshPath).suffix
751  if file_extension.lower() == ".dae":
752  obj = DaeMeshGeometry(geometry_object.meshPath)
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)
757  else:
758  msg = f"Unknown mesh file format: {geometry_object.meshPath}."
759  warnings.warn(msg, category=UserWarning, stacklevel=2)
760  obj = None
761 
762  return obj
763 
764  def loadViewerGeometryObject(self, geometry_object, geometry_type, color=None):
765  """Load a single geometry object"""
766  node_name = self.getViewerNodeName(geometry_object, geometry_type)
767  meshcat_node = self.viewer[node_name]
768 
769  is_mesh = False
770  try:
771  obj = None
772  if WITH_HPP_FCL_BINDINGS:
773  if isinstance(geometry_object.geometry, hppfcl.ShapeBase):
774  obj = self.loadPrimitive(geometry_object)
775  elif (
776  tuple(map(int, hppfcl.__version__.split("."))) >= (3, 0, 0)
777  and hppfcl.WITH_OCTOMAP
778  and isinstance(geometry_object.geometry, hppfcl.OcTree)
779  ):
780  obj = loadOctree(geometry_object.geometry)
781  elif hasMeshFileInfo(geometry_object):
782  obj = self.loadMeshFromFile(geometry_object)
783  is_mesh = True
784  elif isinstance(
785  geometry_object.geometry,
786  (
787  hppfcl.BVHModelBase,
788  hppfcl.HeightFieldOBBRSS,
789  hppfcl.HeightFieldAABB,
790  ),
791  ):
792  obj = loadMesh(geometry_object.geometry)
793  if obj is None and hasMeshFileInfo(geometry_object):
794  obj = self.loadMeshFromFile(geometry_object)
795  is_mesh = True
796  if obj is None:
797  msg = (
798  "The geometry object named "
799  + geometry_object.name
800  + " is not supported by Pinocchio/MeshCat for vizualization."
801  )
802  warnings.warn(msg, category=UserWarning, stacklevel=2)
803  return
804  except Exception as e:
805  msg = (
806  "Error while loading geometry object: "
807  f"{geometry_object.name}\nError message:\n{e}"
808  )
809  warnings.warn(msg, category=UserWarning, stacklevel=2)
810  return
811 
812  if isinstance(obj, mg.Object):
813  meshcat_node.set_object(obj)
814  elif isinstance(obj, (mg.Geometry, mg.ReferenceSceneElement)):
815  material = mg.MeshPhongMaterial()
816  # Set material color from URDF, converting for triplet of doubles to a
817  # single int.
818 
819  def to_material_color(rgba) -> int:
820  """Convert rgba color as list into rgba color as int"""
821  return (
822  int(rgba[0] * 255) * 256**2
823  + int(rgba[1] * 255) * 256
824  + int(rgba[2] * 255)
825  )
826 
827  if color is None:
828  meshColor = geometry_object.meshColor
829  else:
830  meshColor = color
831  # Add transparency, if needed.
832  material.color = to_material_color(meshColor)
833 
834  if float(meshColor[3]) != 1.0:
835  material.transparent = True
836  material.opacity = float(meshColor[3])
837 
838  geom_material = geometry_object.meshMaterial
839  if geometry_object.overrideMaterial and isinstance(
840  geom_material, pin.GeometryPhongMaterial
841  ):
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
845 
846  if isinstance(obj, DaeMeshGeometry):
847  obj.path = meshcat_node.path
848  scale = list(np.asarray(geometry_object.meshScale).flatten())
849  obj.set_scale(scale)
850  if geometry_object.overrideMaterial:
851  obj.material = material
852  meshcat_node.window.send(obj)
853  else:
854  meshcat_node.set_object(obj, material)
855 
856  # Apply the scaling
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)
860 
862  self,
863  rootNodeName="pinocchio",
864  color=None,
865  collision_color=None,
866  visual_color=None,
867  ):
868  """Load the robot in a MeshCat viewer.
869  Parameters:
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
877  (between 0 and 1)
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
880  (between 0 and 1)
881  """
882  if color is not None:
883  warnings.warn(
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,
888  )
889  collision_color = color
890  visual_color = color
891 
892  # Set viewer to use to gepetto-gui.
893  self.viewerRootNodeName = rootNodeName
894 
895  # Collisions
896  self.viewerCollisionGroupName = self.viewerRootNodeName + "/" + "collisions"
897 
898  if self.collision_model is not None:
899  for collision in self.collision_model.geometryObjects:
901  collision, pin.GeometryType.COLLISION, collision_color
902  )
903  self.displayCollisions(False)
904 
905  # Visuals
906  self.viewerVisualGroupName = self.viewerRootNodeName + "/" + "visuals"
907  if self.visual_model is not None:
908  for visual in self.visual_model.geometryObjects:
910  visual, pin.GeometryType.VISUAL, visual_color
911  )
912  self.displayVisuals(True)
913 
914  # Frames
915  self.viewerFramesGroupName = self.viewerRootNodeName + "/" + "frames"
916  self.displayFrames(False)
917 
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
922  else:
923  geom_model = self.collision_model
924  geometry_type = pin.GeometryType.COLLISION
925 
926  geom_id = geom_model.getGeometryId(new_geometry_object.name)
927  geom_model.geometryObjects[geom_id] = new_geometry_object
928 
929  self.delete(new_geometry_object, geometry_type)
930  visual = geom_model.geometryObjects[geom_id]
931  self.loadViewerGeometryObject(visual, geometry_type)
932 
933  def clean(self):
934  self.viewer.delete()
935 
936  def delete(self, geometry_object, geometry_type):
937  viewer_name = self.getViewerNodeName(geometry_object, geometry_type)
938  self.viewer[viewer_name].delete()
939 
940  def display(self, q=None):
941  """
942  Display the robot at configuration q in the viewer by placing all the bodies
943  """
944  if q is not None:
945  pin.forwardKinematics(self.model, self.data, q)
946 
947  if self.display_collisions:
948  self.updatePlacements(pin.GeometryType.COLLISION)
949 
950  if self.display_visuals:
951  self.updatePlacements(pin.GeometryType.VISUAL)
952 
953  if self.display_frames:
954  self.updateFrames()
955 
956  def updatePlacements(self, geometry_type):
957  if geometry_type == pin.GeometryType.VISUAL:
958  geom_model = self.visual_model
959  geom_data = self.visual_data
960  else:
961  geom_model = self.collision_model
962  geom_data = self.collision_data
963 
964  pin.updateGeometryPlacements(self.model, self.data, geom_model, geom_data)
965  for visual in geom_model.geometryObjects:
966  visual_name = self.getViewerNodeName(visual, geometry_type)
967  # Get mesh pose.
968  M = geom_data.oMg[geom_model.getGeometryId(visual.name)]
969  # Manage scaling: force scaling even if this should be normally handled by
970  # MeshCat (but there is a bug here)
971  geom = visual.geometry
972  if WITH_HPP_FCL_BINDINGS and isinstance(
973  geom, (hppfcl.Plane, hppfcl.Halfspace)
974  ):
975  T = M.copy()
976  T.translation += M.rotation @ (geom.d * geom.n)
977  T = T.homogeneous
978  else:
979  T = M.homogeneous
980 
981  # Update viewer configuration.
982  self.viewer[visual_name].set_transform(T)
983 
984  for visual in self.static_objects:
985  visual_name = self.getViewerNodeName(visual, pin.GeometryType.VISUAL)
986  M: pin.SE3 = visual.placement
987  T = M.homogeneous
988  self.viewer[visual_name].set_transform(T)
989 
990  def addGeometryObject(self, obj: pin.GeometryObject, color=None):
991  """Add a visual GeometryObject to the viewer, with an optional color."""
992  self.loadViewerGeometryObject(obj, pin.GeometryType.VISUAL, color)
993  self.static_objects.append(obj)
994 
996  if not hasattr(self.viewer, "get_image"):
997  warnings.warn(
998  "meshcat.Visualizer does not have the get_image() method."
999  " You need meshcat >= 0.2.0 to get this feature."
1000  )
1001 
1002  def captureImage(self, w=None, h=None):
1003  """Capture an image from the Meshcat viewer and return an RGB array."""
1004  if w is not None or h is not None:
1005  # pass arguments when either is not None
1006  img = self.viewer.get_image(w, h)
1007  else:
1008  img = self.viewer.get_image()
1009  img_arr = np.asarray(img)
1010  return img_arr
1011 
1012  def displayCollisions(self, visibility):
1013  """Set whether to display collision objects or not."""
1014  if self.collision_model is None:
1015  self.display_collisions = False
1016  else:
1017  self.display_collisions = visibility
1018  self.viewer[self.viewerCollisionGroupName].set_property("visible", visibility)
1019 
1020  if visibility:
1021  self.updatePlacements(pin.GeometryType.COLLISION)
1022 
1023  def displayVisuals(self, visibility):
1024  """Set whether to display visual objects or not."""
1025  if self.visual_model is None:
1026  self.display_visuals = False
1027  else:
1028  self.display_visuals = visibility
1029  self.viewer[self.viewerVisualGroupName].set_property("visible", visibility)
1030 
1031  if visibility:
1032  self.updatePlacements(pin.GeometryType.VISUAL)
1033 
1034  def displayFrames(self, visibility, frame_ids=None, axis_length=0.2, axis_width=2):
1035  """Set whether to display frames or not."""
1036  self.display_frames = visibility
1037  if visibility:
1038  self.initializeFrames(frame_ids, axis_length, axis_width)
1039  self.viewer[self.viewerFramesGroupName].set_property("visible", visibility)
1040 
1041  def initializeFrames(self, frame_ids=None, axis_length=0.2, axis_width=2):
1042  """Initializes the frame objects for display."""
1043  import meshcat.geometry as mg
1044 
1045  self.viewer[self.viewerFramesGroupName].delete()
1046  self.frame_ids = []
1047 
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(
1052  mg.LineSegments(
1053  mg.PointsGeometry(
1054  position=axis_length * FRAME_AXIS_POSITIONS,
1055  color=FRAME_AXIS_COLORS,
1056  ),
1057  mg.LineBasicMaterial(
1058  linewidth=axis_width,
1059  vertexColors=True,
1060  ),
1061  )
1062  )
1063  self.frame_ids.append(fid)
1064 
1065  def updateFrames(self):
1066  """
1067  Updates the frame visualizations with the latest transforms from model data.
1068  """
1069  pin.updateFramePlacements(self.model, self.data)
1070  for fid in self.frame_ids:
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)
1074 
1075  def drawFrameVelocities(self, frame_id: int, v_scale=0.2, color=FRAME_VEL_COLOR):
1076  pin.updateFramePlacement(self.model, self.data, frame_id)
1077  vFr = pin.getFrameVelocity(
1078  self.model, self.data, frame_id, pin.LOCAL_WORLD_ALIGNED
1079  )
1080  line_group_name = f"ee_vel/{frame_id}"
1082  [v_scale * vFr.linear], [frame_id], [line_group_name], [color]
1083  )
1084 
1086  self,
1087  vecs: List[np.ndarray],
1088  frame_ids: List[int],
1089  vec_names: List[str],
1090  colors: List[int],
1091  ):
1092  """Draw vectors extending from given frames."""
1093  import meshcat.geometry as mg
1094 
1095  if len(vecs) != len(frame_ids) or len(vecs) != len(vec_names):
1096  return ValueError(
1097  "Number of vectors and frames IDs or names is inconsistent."
1098  )
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
1102  name = vec_names[i]
1103  geometry = mg.PointsGeometry(position=vertices)
1104  geom_object = mg.LineSegments(
1105  geometry, mg.LineBasicMaterial(color=colors[i])
1106  )
1107  prefix = self.viewerVisualGroupName + "/lines/" + name
1108  self.viewer[prefix].set_object(geom_object)
1109 
1110 
1111 __all__ = ["MeshcatVisualizer"]
pinocchio.visualize.meshcat_visualizer.Plane.widthSegments
widthSegments
Definition: meshcat_visualizer.py:192
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.clean
def clean(self)
Definition: meshcat_visualizer.py:933
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer._node_default_cam
_node_default_cam
Definition: meshcat_visualizer.py:607
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer._check_meshcat_has_get_image
def _check_meshcat_has_get_image(self)
Definition: meshcat_visualizer.py:995
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.setCameraTarget
def setCameraTarget(self, np.ndarray target)
Definition: meshcat_visualizer.py:642
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.setCameraPreset
def setCameraPreset(self, str preset_key)
Definition: meshcat_visualizer.py:648
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.path
path
Definition: meshcat_visualizer.py:115
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.__init__
None __init__(self, str dae_path, Optional[Set[str]] cache=None)
Definition: meshcat_visualizer.py:104
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.displayFrames
def displayFrames(self, visibility, frame_ids=None, axis_length=0.2, axis_width=2)
Definition: meshcat_visualizer.py:1034
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.captureImage
def captureImage(self, w=None, h=None)
Definition: meshcat_visualizer.py:1002
pinocchio.visualize.meshcat_visualizer.getColor
def getColor(color)
Definition: meshcat_visualizer.py:54
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.loadViewerGeometryObject
def loadViewerGeometryObject(self, geometry_object, geometry_type, color=None)
Definition: meshcat_visualizer.py:764
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.displayVisuals
def displayVisuals(self, visibility)
Definition: meshcat_visualizer.py:1023
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer._rot_cam_key
_rot_cam_key
Definition: meshcat_visualizer.py:609
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.img_resources
img_resources
Definition: meshcat_visualizer.py:135
pinocchio.visualize.meshcat_visualizer.Plane.height
height
Definition: meshcat_visualizer.py:191
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.viewerVisualGroupName
viewerVisualGroupName
Definition: meshcat_visualizer.py:900
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.loadPrimitive
def loadPrimitive(self, pin.GeometryObject geometry_object)
Definition: meshcat_visualizer.py:668
pinocchio.visualize.meshcat_visualizer.loadMesh
def loadMesh(mesh)
Definition: meshcat_visualizer.py:288
pinocchio.visualize.meshcat_visualizer.Cone.__init__
def __init__(self, float height, float radius, float radialSegments=32, bool openEnded=False)
Definition: meshcat_visualizer.py:80
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.initViewer
def initViewer(self, viewer=None, open=False, loadModel=False, zmq_url=None)
Definition: meshcat_visualizer.py:598
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.frame_ids
frame_ids
Definition: meshcat_visualizer.py:1046
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.reload
def reload(self, new_geometry_object, geometry_type=None)
Definition: meshcat_visualizer.py:918
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.display_collisions
display_collisions
Definition: meshcat_visualizer.py:1015
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry
Definition: meshcat_visualizer.py:103
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.viewer
viewer
Definition: meshcat_visualizer.py:605
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.__init__
def __init__(self, model=pin.Model(), collision_model=None, visual_model=None, copy_models=False, data=None, collision_data=None, visual_data=None)
Definition: meshcat_visualizer.py:562
pinocchio.visualize.meshcat_visualizer.Cone.radialSegments
radialSegments
Definition: meshcat_visualizer.py:84
simulation-pendulum.type
type
Definition: simulation-pendulum.py:19
pinocchio.visualize.meshcat_visualizer.Plane.heightSegments
heightSegments
Definition: meshcat_visualizer.py:193
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.addGeometryObject
def addGeometryObject(self, pin.GeometryObject obj, color=None)
Definition: meshcat_visualizer.py:990
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.viewerCollisionGroupName
viewerCollisionGroupName
Definition: meshcat_visualizer.py:890
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.displayCollisions
def displayCollisions(self, visibility)
Definition: meshcat_visualizer.py:1012
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.initializeFrames
def initializeFrames(self, frame_ids=None, axis_length=0.2, axis_width=2)
Definition: meshcat_visualizer.py:1041
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.viewerRootNodeName
viewerRootNodeName
Definition: meshcat_visualizer.py:887
pinocchio.visualize.meshcat_visualizer.Plane
Definition: meshcat_visualizer.py:185
pinocchio.visualize.meshcat_visualizer.loadPrimitive
def loadPrimitive(geometry_object)
Definition: meshcat_visualizer.py:428
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.display_frames
display_frames
Definition: meshcat_visualizer.py:1036
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.updatePlacements
def updatePlacements(self, geometry_type)
Definition: meshcat_visualizer.py:956
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.static_objects
static_objects
Definition: meshcat_visualizer.py:580
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.lower
Dict[str, Any] lower(self)
Definition: meshcat_visualizer.py:155
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.drawFrameVelocities
def drawFrameVelocities(self, int frame_id, v_scale=0.2, color=FRAME_VEL_COLOR)
Definition: meshcat_visualizer.py:1075
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.setCameraPose
def setCameraPose(self, pose)
Definition: meshcat_visualizer.py:659
pinocchio.visualize.meshcat_visualizer.Cone.height
height
Definition: meshcat_visualizer.py:83
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.viewerFramesGroupName
viewerFramesGroupName
Definition: meshcat_visualizer.py:909
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.material
material
Definition: meshcat_visualizer.py:116
pinocchio.visualize.meshcat_visualizer.loadOctree
def loadOctree(hppfcl.OcTree octree)
Definition: meshcat_visualizer.py:218
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.display
def display(self, q=None)
Definition: meshcat_visualizer.py:940
pinocchio.visualize.meshcat_visualizer.Plane.lower
MsgType lower(self, Any object_data)
Definition: meshcat_visualizer.py:201
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.loadMeshFromFile
def loadMeshFromFile(self, geometry_object)
Definition: meshcat_visualizer.py:739
pinocchio::toRotationMatrix
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
Definition: rotation.hpp:26
pinocchio.utils.npToTuple
def npToTuple(M)
Definition: bindings/python/pinocchio/utils.py:22
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.display_visuals
display_visuals
Definition: meshcat_visualizer.py:1026
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.intrinsic_transform
intrinsic_transform
Definition: meshcat_visualizer.py:117
pinocchio.visualize.meshcat_visualizer.Plane.__init__
def __init__(self, float width, float height, float widthSegments=1, float heightSegments=1)
Definition: meshcat_visualizer.py:188
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:540
pinocchio.visualize.meshcat_visualizer.createCapsule
def createCapsule(length, radius, radial_resolution=30, cap_resolution=10)
Definition: meshcat_visualizer.py:470
append-urdf-model-with-another-model.open
open
Definition: append-urdf-model-with-another-model.py:77
pinocchio.visualize.meshcat_visualizer.Cone.lower
MsgType lower(self, Any object_data)
Definition: meshcat_visualizer.py:93
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.setBackgroundColor
def setBackgroundColor(self, str preset_name="gray", col_top=None, col_bot=None)
Definition: meshcat_visualizer.py:631
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.setCameraZoom
def setCameraZoom(self, float zoom)
Definition: meshcat_visualizer.py:655
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.disableCameraControl
def disableCameraControl(self)
Definition: meshcat_visualizer.py:662
boost::fusion::append
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Definition: fusion.hpp:32
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.getViewerNodeName
def getViewerNodeName(self, geometry_object, geometry_type)
Definition: meshcat_visualizer.py:591
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer._draw_vectors_from_frame
def _draw_vectors_from_frame(self, List[np.ndarray] vecs, List[int] frame_ids, List[str] vec_names, List[int] colors)
Definition: meshcat_visualizer.py:1085
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.loadViewerModel
def loadViewerModel(self, rootNodeName="pinocchio", color=None, collision_color=None, visual_color=None)
Definition: meshcat_visualizer.py:861
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.delete
def delete(self, geometry_object, geometry_type)
Definition: meshcat_visualizer.py:936
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.enableCameraControl
def enableCameraControl(self)
Definition: meshcat_visualizer.py:665
pinocchio.visualize.meshcat_visualizer.Plane.width
width
Definition: meshcat_visualizer.py:190
pinocchio.visualize.meshcat_visualizer.hasMeshFileInfo
def hasMeshFileInfo(geometry_object)
Definition: meshcat_visualizer.py:61
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer._node_background
_node_background
Definition: meshcat_visualizer.py:608
pinocchio.visualize.meshcat_visualizer.Cone.openEnded
openEnded
Definition: meshcat_visualizer.py:85
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.dae_raw
dae_raw
Definition: meshcat_visualizer.py:122
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:181
pinocchio.visualize.meshcat_visualizer.Cone.radius
radius
Definition: meshcat_visualizer.py:82
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.reset
def reset(self)
Definition: meshcat_visualizer.py:627
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.setCameraPosition
def setCameraPosition(self, np.ndarray position)
Definition: meshcat_visualizer.py:645
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer.updateFrames
def updateFrames(self)
Definition: meshcat_visualizer.py:1065
pinocchio.visualize.meshcat_visualizer.DaeMeshGeometry.set_scale
None set_scale(self, scale)
Definition: meshcat_visualizer.py:180
pinocchio.visualize.meshcat_visualizer.Cone
Definition: meshcat_visualizer.py:75


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:47