5 import pinocchio
as pin
9 from os.path import dirname, join, abspath
15 pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))),
"models")
17 model_path = join(pinocchio_model_dir,
"example-robot-data/robots")
18 mesh_dir = pinocchio_model_dir
19 urdf_filename =
"panda.urdf" 20 urdf_model_path = join(join(model_path,
"panda_description/urdf"),urdf_filename)
22 model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_model_path, mesh_dir)
26 points = np.random.rand(3, num_points)
27 point_cloud_placement = pin.SE3.Identity()
28 point_cloud_placement.translation = np.array([0.2,0.2,-0.5])
35 x_grid = np.linspace(0.,1.,nx)
36 x_half_pad = 0.5*(x_grid[1] - x_grid[0])
37 x_bins = np.digitize(X, x_grid + x_half_pad)
38 x_dim = x_grid[-1] - x_grid[0]
41 y_grid = np.linspace(0.,1.,ny)
42 y_half_pad = 0.5*(y_grid[1] - y_grid[0])
43 y_bins = np.digitize(Y, y_grid + y_half_pad)
44 y_dim = y_grid[-1] - y_grid[0]
46 point_bins = y_bins * nx + x_bins
47 heights = np.zeros((ny, nx))
48 np.maximum.at(heights.ravel(), point_bins, Z)
50 point_cloud = fcl.BVHModelOBBRSS()
51 point_cloud.beginModel(0, num_points)
52 point_cloud.addVertices(points.T)
54 height_field = fcl.HeightFieldOBBRSS(x_dim, y_dim, heights,
min(Z))
55 height_field_placement = point_cloud_placement * pin.SE3(np.eye(3), 0.5*np.array([x_grid[0] + x_grid[-1], y_grid[0] + y_grid[-1], 0.]))
57 go_point_cloud = pin.GeometryObject(
"point_cloud",0,point_cloud,point_cloud_placement)
58 go_point_cloud.meshColor = np.ones((4))
59 collision_model.addGeometryObject(go_point_cloud)
60 visual_model.addGeometryObject(go_point_cloud)
62 go_height_field = pin.GeometryObject(
"height_field",0,height_field,height_field_placement)
63 go_height_field.meshColor = np.ones((4))
64 height_field_collision_id = collision_model.addGeometryObject(go_height_field)
65 visual_model.addGeometryObject(go_height_field)
68 panda_hand_collision_id = collision_model.getGeometryId(
"panda_hand_0")
69 go_panda_hand = collision_model.geometryObjects[panda_hand_collision_id]
70 go_panda_hand.geometry.buildConvexRepresentation(
False)
71 go_panda_hand.geometry = go_panda_hand.geometry.convex
73 collision_pair = pin.CollisionPair(height_field_collision_id, panda_hand_collision_id)
74 collision_model.addCollisionPair(collision_pair)
85 viz.initViewer(open=
True)
86 except ImportError
as err:
87 print(
"Error while initializing the viewer. It seems you should install Python meshcat")
95 q0 = pin.neutral(model)
99 data = model.createData()
100 collision_data = collision_model.createData()
101 while not is_collision:
102 q = pin.randomConfiguration(model)
104 is_collision = pin.computeCollisions(model, data, collision_model, collision_data, q,
True)
106 print(
"Found a configuration in collision:",q)
JointCollectionTpl const DataTpl< Scalar, Options, JointCollectionTpl > const Eigen::MatrixBase< Mat > & min