collisions.py
Go to the documentation of this file.
1 from os.path import abspath, dirname, join
2 
3 import pinocchio as pin
4 
5 pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))), "models")
6 
7 model_path = join(pinocchio_model_dir, "example-robot-data/robots")
8 mesh_dir = pinocchio_model_dir
9 urdf_filename = "romeo_small.urdf"
10 urdf_model_path = join(join(model_path, "romeo_description/urdf"), urdf_filename)
11 
12 # Load model
13 model = pin.buildModelFromUrdf(urdf_model_path, pin.JointModelFreeFlyer())
14 
15 # Load collision geometries
16 geom_model = pin.buildGeomFromUrdf(
17  model, urdf_model_path, pin.GeometryType.COLLISION, mesh_dir
18 )
19 
20 # Add collisition pairs
21 geom_model.addAllCollisionPairs()
22 print("num collision pairs - initial:", len(geom_model.collisionPairs))
23 
24 # Remove collision pairs listed in the SRDF file
25 srdf_filename = "romeo.srdf"
26 srdf_model_path = model_path + "/romeo_description/srdf/" + srdf_filename
27 
28 pin.removeCollisionPairs(model, geom_model, srdf_model_path)
29 print(
30  "num collision pairs - after removing useless collision pairs:",
31  len(geom_model.collisionPairs),
32 )
33 
34 # Load reference configuration
35 pin.loadReferenceConfigurations(model, srdf_model_path)
36 
37 # Retrieve the half sitting position from the SRDF file
38 q = model.referenceConfigurations["half_sitting"]
39 
40 # Create data structures
41 data = model.createData()
42 geom_data = pin.GeometryData(geom_model)
43 
44 
45 # Compute all the collisions
46 pin.computeCollisions(model, data, geom_model, geom_data, q, False)
47 
48 # Print the status of collision for all collision pairs
49 for k in range(len(geom_model.collisionPairs)):
50  cr = geom_data.collisionResults[k]
51  cp = geom_model.collisionPairs[k]
52  print(
53  "collision pair:",
54  cp.first,
55  ",",
56  cp.second,
57  "- collision:",
58  "Yes" if cr.isCollision() else "No",
59  )
60 
61 # Compute for a single pair of collision
62 pin.updateGeometryPlacements(model, data, geom_model, geom_data, q)
63 pin.computeCollision(geom_model, geom_data, 0)


pinocchio
Author(s):
autogenerated on Wed Sep 25 2024 02:42:23