22 #include <boost/test/unit_test.hpp>
26 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
32 + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
42 std::vector<std::string> package_paths(1, package_path);
47 const size_t num_thread = (size_t)omp_get_max_threads();
77 const size_t num_thread = (size_t)omp_get_max_threads();
82 auto manager =
pool.getBroadPhaseManager(0);
85 BOOST_CHECK(
pool.check());
93 qs.col(
i).tail<4>() = Eigen::Quaterniond(
placement.rotation()).coeffs();
96 typedef Eigen::Matrix<bool, Eigen::Dynamic, 1> VectorBool;
110 BOOST_CHECK(
res == res_ref);
112 res_all_before_ref[
i] = res_ref;
117 BOOST_CHECK(res_all_before == res_all_before_ref);
122 geom_model.geometryObjects[obj2_index].geometry->computeLocalAABB();
127 geom_model_pool.geometryObjects[obj2_index] =
geom_model.geometryObjects[obj2_index].clone();
143 BOOST_CHECK(
res == res_ref);
145 res_all_intermediate_ref[
i] = res_ref;
150 BOOST_CHECK(res_all_intermediate == res_all_intermediate_ref);
153 BOOST_CHECK(res_all_intermediate != res_all_before);
159 new_sphere2_ptr->computeLocalAABB();
160 geom_model.geometryObjects[obj2_index].geometry = new_sphere2_ptr;
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());
167 *
geom_model.geometryObjects[obj2_index].geometry.get() == *new_sphere2_ptr.get()->clone());
171 geom_model_pool.geometryObjects[obj2_index] =
geom_model.geometryObjects[obj2_index].clone();
174 BOOST_CHECK(not
pool.check());
176 BOOST_CHECK(
pool.check());
189 BOOST_CHECK(
res == res_ref);
191 res_all_final_ref[
i] = res_ref;
196 BOOST_CHECK(res_all_final == res_all_final_ref);
199 BOOST_CHECK(res_all_final == res_all_before);
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;
213 + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
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);
231 GeometryData geometry_data(geometry_model), geometry_data_ref(geometry_model);
233 const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(
model.nq);
239 BOOST_CHECK(res_ref ==
res);
240 BOOST_CHECK(geometry_data_ref.collisionPairIndex == geometry_data.collisionPairIndex);
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]);
248 geometry_data_ref.collisionResults[k].getContacts()
249 == geometry_data.collisionResults[k].getContacts());
257 + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
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);
279 const size_t num_thread = (size_t)omp_get_max_threads();
284 const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(
model.nq);
292 delete geometry_model_ptr;
294 typedef Eigen::Matrix<bool, Eigen::Dynamic, 1>
VectorXb;
303 + std::string(
"/example-robot-data/robots/talos_data/robots/talos_reduced.urdf");
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);
323 const Eigen::VectorXd qmax = Eigen::VectorXd::Ones(
model.nq);
325 const size_t num_thread = (size_t)omp_get_max_threads();
333 typedef Eigen::Matrix<bool, Eigen::Dynamic, 1>
VectorXb;
341 BOOST_CHECK(res_ref.sum() > 0);
349 BOOST_CHECK(
res == res_ref);
363 BOOST_CHECK(res1 == res_ref);
364 BOOST_CHECK(res2 == res_ref);
366 for (Eigen::DenseIndex k = 0; k <
batch_size; ++k)
369 BOOST_CHECK(res_ref[k]);
371 BOOST_CHECK(res_ref[k]);
386 BOOST_CHECK(res1 == res_ref);
387 BOOST_CHECK(res2 == res_ref);
389 for (Eigen::DenseIndex k = 0; k <
batch_size; ++k)
392 BOOST_CHECK(res_ref[k]);
394 BOOST_CHECK(res_ref[k]);
399 BOOST_AUTO_TEST_SUITE_END()