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


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