parallel-geometry.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021-2023 INRIA
3 //
4 
5 #include <iostream>
6 
17 
20 
21 #include <vector>
22 #include <boost/test/unit_test.hpp>
23 
24 using namespace pinocchio;
25 
26 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
27 
28 BOOST_AUTO_TEST_CASE(test_geometry_pool)
29 {
30  const std::string filename =
32  + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
33 
36  Data data(model);
37 
38  const std::string package_path = PINOCCHIO_MODEL_DIR;
39  hpp::fcl::MeshLoaderPtr mesh_loader = std::make_shared<hpp::fcl::CachedMeshLoader>();
40  const std::string srdf_filename =
41  PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
42  std::vector<std::string> package_paths(1, package_path);
43  pinocchio::GeometryModel geometry_model;
45  model, filename, COLLISION, geometry_model, package_paths, mesh_loader);
46 
47  const size_t num_thread = (size_t)omp_get_max_threads();
48  pinocchio::GeometryModel geometry_model_empty;
49  GeometryPool pool(model, geometry_model_empty, num_thread);
50 
51  pool.update(GeometryData(geometry_model));
52 }
53 
54 BOOST_AUTO_TEST_CASE(test_broadphase_pool)
55 {
56  Model model;
57  model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "ff");
58 
59  Data data(model);
61 
64 
65  GeometryObject obj1("obj1", 1, SE3::Identity(), sphere_ptr);
66  geom_model.addGeometryObject(obj1);
67 
68  GeometryObject obj2("obj2", 0, SE3::Identity(), sphere2_ptr);
69  const GeomIndex obj2_index = geom_model.addGeometryObject(obj2);
70 
71  geom_model.addAllCollisionPairs();
72 
73  const GeometryModel geom_model_clone = geom_model.clone();
74 
75  // GeometryObject & go1 = geom_model.geometryObjects[obj_index];
76 
77  const size_t num_thread = (size_t)omp_get_max_threads();
81 
82  auto manager = pool.getBroadPhaseManager(0);
83  GeometryData & geom_data = manager.getGeometryData();
84 
85  BOOST_CHECK(pool.check());
86 
87  const int batch_size = 256;
88  Eigen::MatrixXd qs(model.nq, batch_size);
89  for (int i = 0; i < batch_size; ++i)
90  {
91  const SE3 placement = SE3::Random();
92  qs.col(i).head<3>() = 0.3 * placement.translation();
93  qs.col(i).tail<4>() = Eigen::Quaterniond(placement.rotation()).coeffs();
94  }
95 
96  typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> VectorBool;
97  VectorBool res_all_before(batch_size), res_all_before_ref(batch_size);
98 
99  // Check potential memory leack
100  {
101  Data data_ref(model);
102  GeometryData geom_data_ref(geom_model);
103 
104  for (int i = 0; i < batch_size; ++i)
105  {
106  const bool res = computeCollisions(model, data, manager, qs.col(i), false);
107  const bool res_ref =
108  computeCollisions(model, data_ref, geom_model, geom_data_ref, qs.col(i), false);
109 
110  BOOST_CHECK(res == res_ref);
111 
112  res_all_before_ref[i] = res_ref;
113  }
114 
115  // Do collision checking
116  computeCollisionsInParallel(num_thread, pool, qs, res_all_before, false);
117  BOOST_CHECK(res_all_before == res_all_before_ref);
118  }
119 
120  static_cast<hpp::fcl::Sphere *>(geom_model.geometryObjects[obj2_index].geometry.get())->radius =
121  100;
122  geom_model.geometryObjects[obj2_index].geometry->computeLocalAABB();
123  BOOST_CHECK(static_cast<hpp::fcl::Sphere *>(sphere2_ptr.get())->radius == 100);
124 
125  for (GeometryModel & geom_model_pool : pool.getGeometryModels())
126  {
127  geom_model_pool.geometryObjects[obj2_index] = geom_model.geometryObjects[obj2_index].clone();
128  }
129 
130  pool.update(geom_data);
131 
132  VectorBool res_all_intermediate(batch_size), res_all_intermediate_ref(batch_size);
133  {
134  Data data_ref(model);
135  GeometryData geom_data_ref(geom_model);
136 
137  for (int i = 0; i < batch_size; ++i)
138  {
139  const bool res = computeCollisions(model, data, manager, qs.col(i), false);
140  const bool res_ref =
141  computeCollisions(model, data_ref, geom_model, geom_data_ref, qs.col(i), false);
142 
143  BOOST_CHECK(res == res_ref);
144 
145  res_all_intermediate_ref[i] = res_ref;
146  }
147 
148  // Do collision checking
149  computeCollisionsInParallel(num_thread, pool, qs, res_all_intermediate, false);
150  BOOST_CHECK(res_all_intermediate == res_all_intermediate_ref);
151  }
152 
153  BOOST_CHECK(res_all_intermediate != res_all_before);
154 
155  static_cast<hpp::fcl::Sphere *>(sphere2_ptr.get())->radius = 0.1;
156 
157  hpp::fcl::CollisionGeometryPtr_t new_sphere2_ptr(
158  new hpp::fcl::Sphere(static_cast<hpp::fcl::Sphere &>(*sphere2_ptr.get())));
159  new_sphere2_ptr->computeLocalAABB();
160  geom_model.geometryObjects[obj2_index].geometry = new_sphere2_ptr;
161  BOOST_CHECK(
162  static_cast<hpp::fcl::Sphere *>(geom_model.geometryObjects[obj2_index].geometry.get())->radius
163  == static_cast<hpp::fcl::Sphere *>(new_sphere2_ptr.get())->radius);
164  BOOST_CHECK(geom_model.geometryObjects[obj2_index].geometry.get() == new_sphere2_ptr.get());
165  BOOST_CHECK(geom_model.geometryObjects[obj2_index].geometry.get() != sphere2_ptr.get());
166  BOOST_CHECK(
167  *geom_model.geometryObjects[obj2_index].geometry.get() == *new_sphere2_ptr.get()->clone());
168 
169  for (GeometryModel & geom_model_pool : pool.getGeometryModels())
170  {
171  geom_model_pool.geometryObjects[obj2_index] = geom_model.geometryObjects[obj2_index].clone();
172  }
173 
174  BOOST_CHECK(not pool.check());
175  pool.update(geom_data);
176  BOOST_CHECK(pool.check());
177 
178  VectorBool res_all_final(batch_size), res_all_final_ref(batch_size);
179  {
180  Data data_ref(model);
181  GeometryData geom_data_ref(geom_model);
182 
183  for (int i = 0; i < batch_size; ++i)
184  {
185  const bool res = computeCollisions(model, data, manager, qs.col(i), false);
186  const bool res_ref =
187  computeCollisions(model, data_ref, geom_model, geom_data_ref, qs.col(i), false);
188 
189  BOOST_CHECK(res == res_ref);
190 
191  res_all_final_ref[i] = res_ref;
192  }
193 
194  // Do collision checking
195  computeCollisionsInParallel(num_thread, pool, qs, res_all_final, false);
196  BOOST_CHECK(res_all_final == res_all_final_ref);
197  }
198 
199  BOOST_CHECK(res_all_final == res_all_before);
200 
201  std::cout << "res_all_before: " << res_all_before.transpose() << std::endl;
202  std::cout << "res_all_before_ref: " << res_all_before_ref.transpose() << std::endl;
203  std::cout << "res_all_intermediate: " << res_all_intermediate.transpose() << std::endl;
204  std::cout << "res_all_intermediate_ref: " << res_all_intermediate_ref.transpose() << std::endl;
205  std::cout << "res_all_final: " << res_all_final.transpose() << std::endl;
206  std::cout << "res_all_final_ref: " << res_all_final_ref.transpose() << std::endl;
207 }
208 
210 {
211  const std::string filename =
213  + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
214 
217  Data data(model), data_ref(model);
218 
219  const std::string package_path = PINOCCHIO_MODEL_DIR;
220  hpp::fcl::MeshLoaderPtr mesh_loader = std::make_shared<hpp::fcl::CachedMeshLoader>();
221  const std::string srdf_filename =
222  PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
223  std::vector<std::string> package_paths(1, package_path);
224  pinocchio::GeometryModel geometry_model;
226  model, filename, COLLISION, geometry_model, package_paths, mesh_loader);
227 
228  geometry_model.addAllCollisionPairs();
230 
231  GeometryData geometry_data(geometry_model), geometry_data_ref(geometry_model);
232 
233  const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
234  Eigen::VectorXd q = randomConfiguration(model, -qmax, qmax);
235 
236  const bool res_ref = computeCollisions(model, data_ref, geometry_model, geometry_data_ref, q);
237  const bool res = computeCollisions(model, data, geometry_model, geometry_data, q);
238 
239  BOOST_CHECK(res_ref == res);
240  BOOST_CHECK(geometry_data_ref.collisionPairIndex == geometry_data.collisionPairIndex);
241 
242  for (size_t k = 0; k < geometry_model.collisionPairs.size(); ++k)
243  {
244  const CollisionPair & cp = geometry_model.collisionPairs[k];
245  BOOST_CHECK(geometry_data_ref.oMg[cp.first] == geometry_data.oMg[cp.first]);
246  BOOST_CHECK(geometry_data_ref.oMg[cp.second] == geometry_data.oMg[cp.second]);
247  BOOST_CHECK(
248  geometry_data_ref.collisionResults[k].getContacts()
249  == geometry_data.collisionResults[k].getContacts());
250  }
251 }
252 
253 BOOST_AUTO_TEST_CASE(test_pool_talos_memory)
254 {
255  const std::string filename =
257  + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
258 
259  pinocchio::Model * model_ptr = new Model();
260  Model & model = *model_ptr;
262  Data data_ref(model);
263 
264  const std::string package_path = PINOCCHIO_MODEL_DIR;
265  hpp::fcl::MeshLoaderPtr mesh_loader = std::make_shared<hpp::fcl::CachedMeshLoader>();
266  const std::string srdf_filename =
267  PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
268  std::vector<std::string> package_paths(1, package_path);
269  pinocchio::GeometryModel * geometry_model_ptr = new GeometryModel();
270  GeometryModel & geometry_model = *geometry_model_ptr;
271  pinocchio::urdf::buildGeom(model, filename, COLLISION, geometry_model, package_paths);
272 
273  geometry_model.addAllCollisionPairs();
275 
278 
279  const size_t num_thread = (size_t)omp_get_max_threads();
280  ;
281  BroadPhaseManagerPool broadphase_manager_pool(model, geometry_model, num_thread);
282 
283  const Eigen::DenseIndex batch_size = 2048;
284  const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
285  Eigen::MatrixXd q(model.nq, batch_size);
286  for (Eigen::DenseIndex i = 0; i < batch_size; ++i)
287  {
288  q.col(i) = randomConfiguration(model, -qmax, qmax);
289  }
290 
291  delete model_ptr;
292  delete geometry_model_ptr;
293 
294  typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> VectorXb;
296  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res);
297 }
298 
299 BOOST_AUTO_TEST_CASE(test_pool_talos)
300 {
301  const std::string filename =
303  + std::string("/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
304 
307  Data data_ref(model);
308 
309  const std::string package_path = PINOCCHIO_MODEL_DIR;
310  hpp::fcl::MeshLoaderPtr mesh_loader = std::make_shared<hpp::fcl::CachedMeshLoader>();
311  const std::string srdf_filename =
312  PINOCCHIO_MODEL_DIR + std::string("/example-robot-data/robots/talos_data/srdf/talos.srdf");
313  std::vector<std::string> package_paths(1, package_path);
314  pinocchio::GeometryModel geometry_model;
316  model, filename, COLLISION, geometry_model, package_paths, mesh_loader);
317 
318  geometry_model.addAllCollisionPairs();
320 
321  GeometryData geometry_data_ref(geometry_model);
322 
323  const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(model.nq);
324  const Eigen::DenseIndex batch_size = 2048;
325  const size_t num_thread = (size_t)omp_get_max_threads();
326 
327  Eigen::MatrixXd q(model.nq, batch_size);
328  for (Eigen::DenseIndex i = 0; i < batch_size; ++i)
329  {
330  q.col(i) = randomConfiguration(model, -qmax, qmax);
331  }
332 
333  typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> VectorXb;
334 
335  VectorXb res_ref(batch_size);
336  res_ref.fill(false);
337  for (Eigen::DenseIndex i = 0; i < batch_size; ++i)
338  {
339  res_ref[i] = computeCollisions(model, data_ref, geometry_model, geometry_data_ref, q.col(i));
340  }
341  BOOST_CHECK(res_ref.sum() > 0);
342 
343  {
345  res.fill(false);
346  GeometryPool geometry_pool(model, geometry_model, num_thread);
347  computeCollisionsInParallel(num_thread, geometry_pool, q, res);
348 
349  BOOST_CHECK(res == res_ref);
350  }
351 
352  {
355 
356  BroadPhaseManagerPool broadphase_manager_pool(model, geometry_model, num_thread);
357  VectorXb res1(batch_size), res2(batch_size), res3(batch_size), res4(batch_size);
358  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res1);
359  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res2, true);
360  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res3, true, true);
361  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res4, false, true);
362 
363  BOOST_CHECK(res1 == res_ref);
364  BOOST_CHECK(res2 == res_ref);
365 
366  for (Eigen::DenseIndex k = 0; k < batch_size; ++k)
367  {
368  if (res3[k])
369  BOOST_CHECK(res_ref[k]);
370  if (res4[k])
371  BOOST_CHECK(res_ref[k]);
372  }
373  }
374 
375  {
378 
379  BroadPhaseManagerPool broadphase_manager_pool(model, geometry_model, num_thread);
380  VectorXb res1(batch_size), res2(batch_size), res3(batch_size), res4(batch_size);
381  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res1);
382  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res2, true);
383  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res3, true, true);
384  computeCollisionsInParallel(num_thread, broadphase_manager_pool, q, res4, false, true);
385 
386  BOOST_CHECK(res1 == res_ref);
387  BOOST_CHECK(res2 == res_ref);
388 
389  for (Eigen::DenseIndex k = 0; k < batch_size; ++k)
390  {
391  if (res3[k])
392  BOOST_CHECK(res_ref[k]);
393  if (res4[k])
394  BOOST_CHECK(res_ref[k]);
395  }
396  }
397 }
398 
399 BOOST_AUTO_TEST_SUITE_END()
broadphase_dynamic_AABB_tree.h
pinocchio::JointModelFreeFlyer
JointModelFreeFlyerTpl< context::Scalar > JointModelFreeFlyer
Definition: multibody/joint/fwd.hpp:110
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::computeCollisions
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
Definition: broadphase.hpp:34
loader.h
pinocchio::BroadPhaseManagerPoolBase
Definition: collision/pool/broadphase-manager.hpp:22
pinocchio::SE3Tpl< context::Scalar, context::Options >
inverse-kinematics.i
int i
Definition: inverse-kinematics.py:20
hpp::fcl::Sphere
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::GeometryObject
Definition: multibody/geometry-object.hpp:87
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
hpp::fcl::CollisionGeometryPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
pinocchio::GeometryData
Definition: multibody/geometry.hpp:233
run-algo-in-parallel.batch_size
int batch_size
Definition: run-algo-in-parallel.py:11
pinocchio::BroadPhaseManagerPool
BroadPhaseManagerPoolTpl< ManagerDerived, Scalar > BroadPhaseManagerPool
Definition: collision/pool/fwd.hpp:35
pinocchio::GeometryModel::addAllCollisionPairs
void addAllCollisionPairs()
Add all possible collision pairs.
pinocchio::randomConfiguration
void randomConfiguration(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorIn1 > &lowerLimits, const Eigen::MatrixBase< ConfigVectorIn2 > &upperLimits, const Eigen::MatrixBase< ReturnType > &qout)
Generate a configuration vector uniformly sampled among provided limits.
Definition: joint-configuration.hpp:325
tree-broadphase-manager.hpp
collision.hpp
pinocchio::TreeBroadPhaseManagerTpl
Definition: collision/pool/fwd.hpp:38
hpp::fcl::Sphere::radius
FCL_REAL radius
geometry.hpp
pinocchio::placement
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
Definition: spatial/classic-acceleration.hpp:122
pinocchio::CollisionPair
Definition: multibody/geometry.hpp:21
pinocchio::urdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::string &filename, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false)
Build the model from a URDF file with a particular joint as root of the model tree inside the model g...
filename
filename
urdf.hpp
srdf.hpp
geometry.hpp
run-algo-in-parallel.pool
pool
Definition: run-algo-in-parallel.py:8
pinocchio::urdf::buildGeom
GeometryModel & buildGeom(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const std::string &filename, const GeometryType type, GeometryModel &geom_model, const std::vector< std::string > &package_paths=std::vector< std::string >(), ::hpp::fcl::MeshLoaderPtr mesh_loader=::hpp::fcl::MeshLoaderPtr())
Build The GeometryModel from a URDF file. Search for meshes in the directories specified by the user ...
collisions.srdf_filename
string srdf_filename
Definition: collisions.py:28
append-urdf-model-with-another-model.geom_model
geom_model
Definition: append-urdf-model-with-another-model.py:26
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
collisions.cp
cp
Definition: collisions.py:54
collisions.geom_data
geom_data
Definition: collisions.py:45
geometry.hpp
pinocchio::SE3Tpl< context::Scalar, context::Options >::Random
static SE3Tpl Random()
Definition: spatial/se3-tpl.hpp:154
pinocchio::GeometryModel::collisionPairs
CollisionPairVector collisionPairs
Vector of collision pairs.
Definition: multibody/geometry.hpp:220
broadphase-manager.hpp
pinocchio::computeCollisionsInParallel
void computeCollisionsInParallel(const size_t num_threads, BroadPhaseManagerPoolBase< BroadPhaseManagerDerived, Scalar, Options, JointCollectionTpl > &pool, const Eigen::MatrixBase< ConfigVectorPool > &q, const Eigen::MatrixBase< CollisionVectorResult > &res, const bool stopAtFirstCollisionInConfiguration=false, const bool stopAtFirstCollisionInBatch=false)
Definition: parallel/broadphase.hpp:26
pinocchio::SE3Tpl< context::Scalar, context::Options >::Identity
static SE3Tpl Identity()
Definition: spatial/se3-tpl.hpp:136
pinocchio::GeometryModel
Definition: multibody/geometry.hpp:50
BOOST_AUTO_TEST_CASE
BOOST_AUTO_TEST_CASE(test_geometry_pool)
Definition: parallel-geometry.cpp:28
pinocchio::COLLISION
@ COLLISION
Definition: multibody/geometry-object.hpp:27
pinocchio::VectorXb
Eigen::Matrix< bool, Eigen::Dynamic, 1 > VectorXb
Definition: fwd.hpp:144
pinocchio::ModelTpl
Definition: context/generic.hpp:20
fwd.hpp
meshcat-viewer.qs
qs
Definition: meshcat-viewer.py:127
pinocchio::GeomIndex
Index GeomIndex
Definition: multibody/fwd.hpp:27
pinocchio::BroadPhaseManagerTpl
Definition: collision/broadphase-manager.hpp:17
pinocchio::Model
ModelTpl< context::Scalar, context::Options > Model
Definition: multibody/fwd.hpp:33
radius
FCL_REAL radius
pinocchio::GeometryPoolTpl
Definition: multibody/pool/fwd.hpp:24
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
BOOST_CHECK
#define BOOST_CHECK(check)
Definition: overview-urdf.cpp:34
PINOCCHIO_MODEL_DIR
#define PINOCCHIO_MODEL_DIR
Definition: build-reduced-model.cpp:11
pinocchio::srdf::removeCollisionPairs
void removeCollisionPairs(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, GeometryModel &geom_model, const std::string &filename, const bool verbose=false)
Deactive all possible collision pairs mentioned in the SRDF file. It throws if the SRDF file is incor...
broadphase.hpp


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:49