collision_multi_threaded_unit.hpp
Go to the documentation of this file.
1 #ifndef TESSERACT_COLLISION_COLLISION_MULTI_THREADED_UNIT_HPP
2 #define TESSERACT_COLLISION_COLLISION_MULTI_THREADED_UNIT_HPP
3 
6 #include <console_bridge/console.h>
7 #include <chrono>
9 
15 
17 {
18 inline void runTest(DiscreteContactManager& checker, bool use_convex_mesh = false)
19 {
20  // Add Meshed Sphere to checker
21  CollisionShapePtr sphere;
22  if (use_convex_mesh)
23  {
24  auto mesh_vertices = std::make_shared<tesseract_common::VectorVector3d>();
25  auto mesh_faces = std::make_shared<Eigen::VectorXi>();
27  EXPECT_GT(
28  loadSimplePlyFile(locator.locateResource("package://tesseract_support/meshes/sphere_p25m.ply")->getFilePath(),
29  *mesh_vertices,
30  *mesh_faces,
31  true),
32  0);
33 
34  auto mesh = std::make_shared<tesseract_geometry::Mesh>(mesh_vertices, mesh_faces);
35  sphere = makeConvexMesh(*mesh);
36  }
37  else
38  {
39  sphere = std::make_shared<tesseract_geometry::Sphere>(0.25);
40  }
41 
42  double delta = 0.55;
43 
44  std::size_t t = 10;
45  std::vector<std::string> link_names;
47  for (std::size_t x = 0; x < t; ++x)
48  {
49  for (std::size_t y = 0; y < t; ++y)
50  {
51  for (std::size_t z = 0; z < t; ++z)
52  {
53  CollisionShapesConst obj3_shapes;
55  Eigen::Isometry3d sphere_pose;
56  sphere_pose.setIdentity();
57 
58  obj3_shapes.push_back(CollisionShapePtr(sphere->clone()));
59  obj3_poses.push_back(sphere_pose);
60 
61  link_names.push_back("sphere_link_" + std::to_string(x) + std::to_string(y) + std::to_string(z));
62 
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);
67  }
68  }
69  }
70 
71  // Check if they are in collision
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));
75 
76  EXPECT_TRUE(checker.getContactAllowedValidator() == nullptr);
77 
78  checker.setCollisionMarginData(CollisionMarginData(0.1));
79  EXPECT_NEAR(checker.getCollisionMarginData().getMaxCollisionMargin(), 0.1, 1e-5);
80  checker.setCollisionObjectsTransform(location);
81 
82  long num_threads = 4;
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();
89 
90  auto start_time = std::chrono::high_resolution_clock::now();
91 
92 #pragma omp parallel for num_threads(num_threads) shared(location)
93  for (long i = 0; i < num_threads; ++i) // NOLINT
94  {
95  const int tn = omp_get_thread_num();
96  CONSOLE_BRIDGE_logDebug("Thread (ID: %i): %i of %i", tn, i, num_threads);
97  const DiscreteContactManager::Ptr& manager = contact_manager[static_cast<size_t>(tn)];
98  for (const auto& co : location)
99  {
100  if (tn == 0)
101  {
102  Eigen::Isometry3d pose = co.second;
103  pose.translation()[0] += 0.1;
104  manager->setCollisionObjectsTransform(co.first, pose);
105  }
106  else if (tn == 1)
107  {
108  Eigen::Isometry3d pose = co.second;
109  pose.translation()[1] += 0.1;
110  std::vector<std::string> names = { co.first };
111  tesseract_common::VectorIsometry3d transforms = { pose };
112  manager->setCollisionObjectsTransform(names, transforms);
113  }
114  else if (tn == 2)
115  {
116  Eigen::Isometry3d pose = co.second;
117  pose.translation()[2] += 0.1;
118  manager->setCollisionObjectsTransform(co.first, pose);
119  }
120  else
121  {
122  Eigen::Isometry3d pose = co.second;
123  pose.translation()[0] -= 0.1;
124  std::vector<std::string> names = { co.first };
125  tesseract_common::VectorIsometry3d transforms = { pose };
126  manager->setCollisionObjectsTransform(names, transforms);
127  }
128  }
129 
130  ContactResultMap result;
131  manager->contactTest(result, ContactRequest(ContactTestType::ALL));
132  result.flattenMoveResults(result_vector[static_cast<size_t>(tn)]);
133  }
134  auto end_time = std::chrono::high_resolution_clock::now();
135 
136  CONSOLE_BRIDGE_logInform("DT: %f ms", std::chrono::duration<double, std::milli>(end_time - start_time).count());
137 
138  for (long i = 0; i < num_threads; ++i)
139  {
140  EXPECT_TRUE(result_vector[static_cast<std::size_t>(i)].size() == 2700);
141  }
142 }
143 } // namespace tesseract_collision::test_suite
144 
145 #endif // TESSERACT_COLLISION_COLLISION_MULTI_THREADED_UNIT_HPP
tesseract_common::VectorIsometry3d
AlignedVector< Eigen::Isometry3d > VectorIsometry3d
resource_locator.h
tesseract_common::TransformMap
AlignedMap< std::string, Eigen::Isometry3d > TransformMap
discrete_contact_manager.h
This is the discrete contact manager base class.
TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
#define TESSERACT_COMMON_IGNORE_WARNINGS_PUSH
tesseract_collision::loadSimplePlyFile
int loadSimplePlyFile(const std::string &path, tesseract_common::VectorVector3d &vertices, Eigen::VectorXi &faces, bool triangles_only=false)
Loads a simple ply file given a path.
Definition: common.cpp:289
convex_hull_utils.h
This is a collection of common methods.
EXPECT_TRUE
#define EXPECT_TRUE(args)
geometries.h
tesseract_collision::makeConvexMesh
tesseract_geometry::ConvexMesh::Ptr makeConvexMesh(const tesseract_geometry::Mesh &mesh)
Definition: convex_hull_utils.cpp:113
tesseract_collision::test_suite
Definition: large_dataset_benchmarks.hpp:17
EXPECT_NEAR
#define EXPECT_NEAR(a, b, prec)
tesseract_collision::CollisionShapePtr
std::shared_ptr< tesseract_geometry::Geometry > CollisionShapePtr
Definition: types.h:50
tesseract_collision::CollisionShapesConst
std::vector< CollisionShapeConstPtr > CollisionShapesConst
Definition: types.h:51
TESSERACT_COMMON_IGNORE_WARNINGS_POP
Definition: create_convex_hull.cpp:37
tesseract_common::GeneralResourceLocator::locateResource
std::shared_ptr< Resource > locateResource(const std::string &url) const override
common.h
This is a collection of common methods.
tesseract_collision::test_suite::runTest
void runTest(ContinuousContactManager &checker)
Definition: collision_box_box_cast_unit.hpp:111
tesseract_common::GeneralResourceLocator
macros.h
tesseract_collision::ContactTestType::ALL
@ ALL
tesseract_collision::DiscreteContactManager::Ptr
std::shared_ptr< DiscreteContactManager > Ptr
Definition: discrete_contact_manager.h:48
tesseract_collision::CollisionMarginData
tesseract_common::CollisionMarginData CollisionMarginData
Definition: types.h:52


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:52