1 #ifndef TESSERACT_COLLISION_COLLISION_MULTI_THREADED_UNIT_HPP
2 #define TESSERACT_COLLISION_COLLISION_MULTI_THREADED_UNIT_HPP
6 #include <console_bridge/console.h>
18 inline void runTest(DiscreteContactManager& checker,
bool use_convex_mesh =
false)
24 auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
25 auto mesh_faces = std::make_shared<Eigen::VectorXi>();
34 auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
39 sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
45 std::vector<std::string> link_names;
47 for (std::size_t x = 0; x < t; ++x)
49 for (std::size_t y = 0; y < t; ++y)
51 for (std::size_t z = 0; z < t; ++z)
55 Eigen::Isometry3d sphere_pose;
56 sphere_pose.setIdentity();
59 obj3_poses.push_back(sphere_pose);
61 link_names.push_back(
"sphere_link_" + std::to_string(x) + std::to_string(y) + std::to_string(z));
63 location[link_names.back()] = sphere_pose;
64 location[link_names.back()].translation() = Eigen::Vector3d(
65 static_cast<double>(x) * delta,
static_cast<double>(y) * delta,
static_cast<double>(z) * delta);
66 checker.addCollisionObject(link_names.back(), 0, obj3_shapes, obj3_poses);
72 checker.setActiveCollisionObjects(link_names);
73 std::vector<std::string> check_active_links = checker.getActiveCollisionObjects();
74 EXPECT_TRUE(tesseract_common::isIdentical<std::string>(link_names, check_active_links,
false));
76 EXPECT_TRUE(checker.getContactAllowedValidator() ==
nullptr);
79 EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
80 checker.setCollisionObjectsTransform(location);
83 std::vector<ContactResultVector> result_vector(
static_cast<std::size_t
>(num_threads));
84 std::vector<DiscreteContactManager::Ptr> contact_manager(
static_cast<std::size_t
>(num_threads));
85 contact_manager[0] = checker.clone();
86 contact_manager[1] = checker.clone();
87 contact_manager[2] = checker.clone();
88 contact_manager[3] = checker.clone();
90 auto start_time = std::chrono::high_resolution_clock::now();
92 #pragma omp parallel for num_threads(num_threads) shared(location)
93 for (
long i = 0; i < num_threads; ++i)
95 const int tn = omp_get_thread_num();
96 CONSOLE_BRIDGE_logDebug(
"Thread (ID: %i): %i of %i", tn, i, num_threads);
98 for (
const auto& co : location)
102 Eigen::Isometry3d pose = co.second;
103 pose.translation()[0] += 0.1;
104 manager->setCollisionObjectsTransform(co.first, pose);
108 Eigen::Isometry3d pose = co.second;
109 pose.translation()[1] += 0.1;
110 std::vector<std::string> names = { co.first };
112 manager->setCollisionObjectsTransform(names, transforms);
116 Eigen::Isometry3d pose = co.second;
117 pose.translation()[2] += 0.1;
118 manager->setCollisionObjectsTransform(co.first, pose);
122 Eigen::Isometry3d pose = co.second;
123 pose.translation()[0] -= 0.1;
124 std::vector<std::string> names = { co.first };
126 manager->setCollisionObjectsTransform(names, transforms);
130 ContactResultMap result;
132 result.flattenMoveResults(result_vector[
static_cast<size_t>(tn)]);
134 auto end_time = std::chrono::high_resolution_clock::now();
136 CONSOLE_BRIDGE_logInform(
"DT: %f ms", std::chrono::duration<double, std::milli>(end_time - start_time).count());
138 for (
long i = 0; i < num_threads; ++i)
140 EXPECT_TRUE(result_vector[
static_cast<std::size_t
>(i)].size() == 2700);
145 #endif // TESSERACT_COLLISION_COLLISION_MULTI_THREADED_UNIT_HPP