reachable-workspace-with-collisions.py
Go to the documentation of this file.
1 import itertools
2 import sys
3 import time
4 from pathlib import Path
5 
6 import meshcat.geometry as g
7 import numpy as np
8 import pinocchio as pin
9 from pinocchio.visualize import MeshcatVisualizer
10 
11 
12 def XYZRPYtoSE3(xyzrpy):
13  rotate = pin.utils.rotate
14  R = rotate("x", xyzrpy[3]) @ rotate("y", xyzrpy[4]) @ rotate("z", xyzrpy[5])
15  p = np.array(xyzrpy[:3])
16  return pin.SE3(R, p)
17 
18 
19 # Load the URDF model.
20 pinocchio_model_dir = Path(__file__).parent.parent / "models"
21 
22 model_path = pinocchio_model_dir / "example-robot-data/robots"
23 mesh_dir = pinocchio_model_dir
24 
25 urdf_path = model_path / "panda_description/urdf/panda.urdf"
26 srdf_path = model_path / "panda_description/srdf/panda.srdf"
27 
28 robot, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_path, mesh_dir)
29 data = robot.createData()
30 
31 # Obstacle map
32 # Capsule obstacles will be placed at these XYZ-RPY parameters
33 oMobs = [
34  [0.40, 0.0, 0.30, np.pi / 2, 0, 0],
35  [-0.08, -0.0, 0.75, np.pi / 2, 0, 0],
36  [0.23, -0.0, 0.04, np.pi / 2, 0, 0],
37 ]
38 
39 # Load visual objects and add them in collision/visual models
40 color = [1.0, 0.2, 0.2, 1.0] # color of the capsules
41 rad, length = 0.1, 0.4 # radius and length of capsules
42 for i, xyzrpy in enumerate(oMobs):
43  obs = pin.GeometryObject.CreateCapsule(rad, length) # Pinocchio obstacle object
44  obs.meshColor = np.array(
45  [1.0, 0.2, 0.2, 1.0]
46  ) # Don't forget me, otherwise I am transparent ...
47  obs.name = "obs%d" % i # Set object name
48  obs.parentJoint = 0 # Set object parent = 0 = universe
49  obs.placement = XYZRPYtoSE3(xyzrpy) # Set object placement wrt parent
50  collision_model.addGeometryObject(obs) # Add object to collision model
51  visual_model.addGeometryObject(obs) # Add object to visual model
52 
53 # Auto-collision pairs
54 collision_model.addAllCollisionPairs()
55 pin.removeCollisionPairs(robot, collision_model, srdf_path)
56 
57 # Collision pairs
58 nobs = len(oMobs)
59 nbodies = collision_model.ngeoms - nobs
60 robotBodies = range(nbodies)
61 envBodies = range(nbodies, nbodies + nobs)
62 for a, b in itertools.product(robotBodies, envBodies):
63  collision_model.addCollisionPair(pin.CollisionPair(a, b))
64 
65 # Geom data
66 # Collision/visual models have been modified => re-generate corresponding data.
67 collision_data = pin.GeometryData(collision_model)
68 visual_data = pin.GeometryData(visual_model)
69 
70 # Start a new MeshCat server and client.
71 viz = MeshcatVisualizer(robot, collision_model, visual_model)
72 try:
73  viz.initViewer(open=True)
74 except ImportError as err:
75  print(
76  "Error while initializing the viewer. "
77  "It seems you should install Python meshcat"
78  )
79  print(err)
80  sys.exit(0)
81 
82 # # Load the robot in the viewer.
83 viz.loadViewerModel()
84 # Display a robot configuration.
85 q0 = (robot.upperPositionLimit.T + robot.lowerPositionLimit.T) / 2
86 horizon = 0.2 # seconds
87 frame = robot.getFrameId(
88  robot.frames[-1].name
89 ) # for example the last frame of the robot
90 n_samples = 5
91 facet_dims = 2
92 
93 # To have convex hull computation or just the points of the reachable workspace and then
94 # compute it with cgal.
95 convex = False
96 
97 if convex:
98  verts, faces = pin.reachableWorkspaceWithCollisionsHull(
99  robot, collision_model, q0, horizon, frame, n_samples, facet_dims
100  )
101  verts = verts.T
102 
103 else:
104  try:
105  from CGAL.CGAL_Alpha_wrap_3 import * # noqa: F403
106  from CGAL.CGAL_Kernel import * # noqa: F403
107  from CGAL.CGAL_Mesh_3 import * # noqa: F403
108  from CGAL.CGAL_Polyhedron_3 import Polyhedron_3
109  except ModuleNotFoundError:
110  print("To compute non convex Polytope CGAL library needs to be installed.")
111  sys.exit(0)
112 
114  return v.x(), v.y(), v.z()
115 
117  p1 = he
118  p2 = p1.next()
119  p3 = p2.next()
120  return [
121  vertex_to_tuple(p1.vertex().point()),
122  vertex_to_tuple(p2.vertex().point()),
123  vertex_to_tuple(p3.vertex().point()),
124  ]
125 
126  def alpha_shape_with_cgal(coords, alpha=None):
127  """
128  Compute the alpha shape of a set of points. (Code thanks to A. Skuric)
129  Retrieved from http://blog.thehumangeo.com/2014/05/12/drawing-boundaries-in-python/
130 
131  :param coords : Coordinates of points
132  :param alpha: List of alpha values to influence the gooeyness of the border.
133  Smaller numbers don't fall inward as much as larger numbers.
134  Too large, and you lose everything!
135  :return: Shapely.MultiPolygons which is the hull of the input set of points
136  """
137  if alpha is None:
138  bbox_diag = np.linalg.norm(np.max(coords, 0) - np.min(coords, 0))
139  alpha_value = bbox_diag / 5
140  else:
141  alpha_value = np.mean(alpha)
142  # Convert to CGAL point
143  points = [Point_3(pt[0], pt[1], pt[2]) for pt in coords] # noqa: F405
144  # Compute alpha shape
145  Q = Polyhedron_3()
146  _a = alpha_wrap_3(points, alpha_value, 0.01, Q) # noqa: F405
147  alpha_shape_vertices = np.array(
148  [vertex_to_tuple(vertex.point()) for vertex in Q.vertices()]
149  )
150 
151  alpha_shape_faces = np.array(
152  [np.array(halfedge_to_triangle(face.halfedge())) for face in Q.facets()]
153  )
154 
155  return alpha_shape_vertices, alpha_shape_faces
156 
157  verts = pin.reachableWorkspaceWithCollisions(
158  robot, collision_model, q0, horizon, frame, n_samples, facet_dims
159  )
160  verts = verts.T
161 
162  alpha = 0.1
163  verts, faces = alpha_shape_with_cgal(verts, alpha)
164  verts = faces.reshape(-1, 3)
165  faces = np.arange(len(verts)).reshape(-1, 3)
166 
167 print("------------------- Display Vertex")
168 
169 
170 # meshcat triangulated mesh
171 poly = g.TriangularMeshGeometry(vertices=verts, faces=faces)
172 viz.viewer["poly"].set_object(
173  poly, g.MeshBasicMaterial(color=0x000000, wireframe=True, linewidth=12, opacity=0.2)
174 )
175 
176 while True:
177  viz.display(q0)
178  viz.viewer["poly"].set_object(
179  poly,
180  g.MeshBasicMaterial(color=0x000000, wireframe=True, linewidth=2, opacity=0.2),
181  )
182 
183  time.sleep(1e-2)
CGAL_Kernel
CGAL_Mesh_3
pinocchio.visualize
Definition: bindings/python/pinocchio/visualize/__init__.py:1
CGAL_Alpha_wrap_3
reachable-workspace-with-collisions.vertex_to_tuple
def vertex_to_tuple(v)
Definition: reachable-workspace-with-collisions.py:113
reachable-workspace-with-collisions.halfedge_to_triangle
def halfedge_to_triangle(he)
Definition: reachable-workspace-with-collisions.py:116
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:576
reachable-workspace-with-collisions.XYZRPYtoSE3
def XYZRPYtoSE3(xyzrpy)
Definition: reachable-workspace-with-collisions.py:12
reachable-workspace-with-collisions.alpha_shape_with_cgal
def alpha_shape_with_cgal(coords, alpha=None)
Definition: reachable-workspace-with-collisions.py:126


pinocchio
Author(s):
autogenerated on Mon Dec 16 2024 03:41:04