reachable-workspace-with-collisions.py
Go to the documentation of this file.
1 import meshcat.geometry as g
2 import pinocchio as pin
3 import numpy as np
4 import sys
5 from os.path import dirname, join, abspath
6 import time
7 import itertools
8 
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 = join(dirname(dirname(str(abspath(__file__)))), "models")
21 
22 model_path = join(pinocchio_model_dir, "example-robot-data/robots")
23 mesh_dir = pinocchio_model_dir
24 
25 urdf_path = join(model_path, "panda_description/urdf/panda.urdf")
26 srdf_path = join(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. It seems you should install Python meshcat"
77  )
78  print(err)
79  sys.exit(0)
80 
81 # # Load the robot in the viewer.
82 viz.loadViewerModel()
83 # Display a robot configuration.
84 q0 = (robot.upperPositionLimit.T + robot.lowerPositionLimit.T) / 2
85 horizon = 0.2 # seconds
86 frame = robot.getFrameId(
87  robot.frames[-1].name
88 ) # for example the last frame of the robot
89 n_samples = 5
90 facet_dims = 2
91 
92 # To have convex hull computation or just the points of the reachable workspace and then compute it with cgal
93 convex = False
94 
95 if convex:
96  verts, faces = pin.reachableWorkspaceWithCollisionsHull(
97  robot, collision_model, q0, horizon, frame, n_samples, facet_dims
98  )
99  verts = verts.T
100 
101 else:
102  try:
103  from CGAL.CGAL_Alpha_wrap_3 import *
104  from CGAL.CGAL_Kernel import *
105  from CGAL.CGAL_Polyhedron_3 import Polyhedron_3
106  from CGAL.CGAL_Mesh_3 import *
107  except ModuleNotFoundError:
108  print("To compute non convex Polytope CGAL library needs to be installed.")
109  sys.exit(0)
110 
112  return v.x(), v.y(), v.z()
113 
115  p1 = he
116  p2 = p1.next()
117  p3 = p2.next()
118  return [
119  vertex_to_tuple(p1.vertex().point()),
120  vertex_to_tuple(p2.vertex().point()),
121  vertex_to_tuple(p3.vertex().point()),
122  ]
123 
124  def alpha_shape_with_cgal(coords, alpha=None):
125  """
126  Compute the alpha shape of a set of points. (Code thanks to A. Skuric)
127  Retrieved from http://blog.thehumangeo.com/2014/05/12/drawing-boundaries-in-python/
128 
129  :param coords : Coordinates of points
130  :param alpha: List of alpha values to influence the gooeyness of the border. Smaller numbers don't fall inward as much as larger numbers.
131  Too large, and you lose everything!
132  :return: Shapely.MultiPolygons which is the hull of the input set of points
133  """
134  if alpha is None:
135  bbox_diag = np.linalg.norm(np.max(coords, 0) - np.min(coords, 0))
136  alpha_value = bbox_diag / 5
137  else:
138  alpha_value = np.mean(alpha)
139  # Convert to CGAL point
140  points = [Point_3(pt[0], pt[1], pt[2]) for pt in coords]
141  # Compute alpha shape
142  Q = Polyhedron_3()
143  a = alpha_wrap_3(points, alpha_value, 0.01, Q)
144  alpha_shape_vertices = np.array(
145  [vertex_to_tuple(vertex.point()) for vertex in Q.vertices()]
146  )
147 
148  alpha_shape_faces = np.array(
149  [np.array(halfedge_to_triangle(face.halfedge())) for face in Q.facets()]
150  )
151 
152  return alpha_shape_vertices, alpha_shape_faces
153 
154  verts = pin.reachableWorkspaceWithCollisions(
155  robot, collision_model, q0, horizon, frame, n_samples, facet_dims
156  )
157  verts = verts.T
158 
159  alpha = 0.1
160  verts, faces = alpha_shape_with_cgal(verts, alpha)
161  verts = faces.reshape(-1, 3)
162  faces = np.arange(len(verts)).reshape(-1, 3)
163 
164 print("------------------- Display Vertex")
165 
166 
167 # meshcat triangulated mesh
168 poly = g.TriangularMeshGeometry(vertices=verts, faces=faces)
169 viz.viewer["poly"].set_object(
170  poly, g.MeshBasicMaterial(color=0x000000, wireframe=True, linewidth=12, opacity=0.2)
171 )
172 
173 while True:
174  viz.display(q0)
175  viz.viewer["poly"].set_object(
176  poly,
177  g.MeshBasicMaterial(color=0x000000, wireframe=True, linewidth=2, opacity=0.2),
178  )
179 
180  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:111
reachable-workspace-with-collisions.halfedge_to_triangle
def halfedge_to_triangle(he)
Definition: reachable-workspace-with-collisions.py:114
pinocchio.visualize.meshcat_visualizer.MeshcatVisualizer
Definition: meshcat_visualizer.py:532
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:124
path


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