1 from pathlib
import Path
3 import pinocchio
as pin
5 pinocchio_model_dir = Path(__file__).parent.parent /
"models"
7 model_path = pinocchio_model_dir /
"example-robot-data/robots"
8 mesh_dir = pinocchio_model_dir
9 urdf_filename =
"romeo_small.urdf"
10 urdf_model_path = model_path /
"romeo_description/urdf" / urdf_filename
13 model = pin.buildModelFromUrdf(urdf_model_path, pin.JointModelFreeFlyer())
16 geom_model = pin.buildGeomFromUrdf(
17 model, urdf_model_path, pin.GeometryType.COLLISION, mesh_dir
21 geom_model.addAllCollisionPairs()
22 print(
"num collision pairs - initial:", len(geom_model.collisionPairs))
25 srdf_filename =
"romeo.srdf"
26 srdf_model_path = model_path /
"romeo_description/srdf" / srdf_filename
28 pin.removeCollisionPairs(model, geom_model, srdf_model_path)
30 "num collision pairs - after removing useless collision pairs:",
31 len(geom_model.collisionPairs),
35 pin.loadReferenceConfigurations(model, srdf_model_path)
38 q = model.referenceConfigurations[
"half_sitting"]
41 data = model.createData()
42 geom_data = pin.GeometryData(geom_model)
46 pin.computeCollisions(model, data, geom_model, geom_data, q,
False)
49 for k
in range(len(geom_model.collisionPairs)):
50 cr = geom_data.collisionResults[k]
51 cp = geom_model.collisionPairs[k]
58 "Yes" if cr.isCollision()
else "No",
62 pin.updateGeometryPlacements(model, data, geom_model, geom_data, q)
63 pin.computeCollision(geom_model, geom_data, 0)