bullet_discrete_bvh_benchmarks.cpp
Go to the documentation of this file.
1 #include <benchmark/benchmark.h>
2 #include <Eigen/Eigen>
3 
9 
10 using namespace tesseract_collision;
11 using namespace test_suite;
12 using namespace tesseract_geometry;
13 
14 int main(int argc, char** argv)
15 {
17  std::make_shared<tesseract_collision_bullet::BulletDiscreteBVHManager>();
18 
20  // Clone
22 
23  {
24  std::vector<int> num_links = { 0, 2, 4, 8, 16, 32, 64, 128, 256, 512 };
25  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_CLONE_FUNC = BM_CLONE;
26  for (const auto& num_link : num_links)
27  {
28  std::string name = "BM_CLONE_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
29  benchmark::RegisterBenchmark(name.c_str(),
30  BM_CLONE_FUNC,
31  DiscreteBenchmarkInfo(checker,
32  CreateUnitPrimative(GeometryType::BOX),
33  Eigen::Isometry3d::Identity(),
34  CreateUnitPrimative(GeometryType::BOX),
35  Eigen::Isometry3d::Identity(),
37  num_link)
38  ->UseRealTime()
39  ->Unit(benchmark::TimeUnit::kMicrosecond);
40  }
41  }
42 
44  // contactTest
46  std::function<void(benchmark::State&, DiscreteBenchmarkInfo)> BM_CONTACT_TEST_FUNC = BM_CONTACT_TEST;
47 
48  // Make vector of all shapes to try
49  std::vector<tesseract_geometry::GeometryType> geometry_types = {
50  GeometryType::BOX, GeometryType::CONE, GeometryType::SPHERE, GeometryType::CAPSULE, GeometryType::CYLINDER
51  };
52 
53  std::vector<ContactTestType> test_types = {
55  };
56 
57  // In Collision
58  {
59  for (const auto& test_type : test_types)
60  {
61  // Loop over all primitive combinations
62  for (const auto& type1 : geometry_types)
63  {
64  for (const auto& type2 : geometry_types)
65  {
66  auto tf = Eigen::Isometry3d::Identity();
67  std::string name = "BM_CONTACT_TEST_0_" + checker->getName() + "_" +
68  ContactTestTypeStrings[static_cast<std::size_t>(test_type)] + "_" +
69  GeometryTypeStrings[static_cast<std::size_t>(type1)] + "_" +
70  GeometryTypeStrings[static_cast<std::size_t>(type2)];
71  benchmark::RegisterBenchmark(name.c_str(),
72  BM_CONTACT_TEST_FUNC,
73  DiscreteBenchmarkInfo(checker,
74  CreateUnitPrimative(type1),
75  Eigen::Isometry3d::Identity(),
76  CreateUnitPrimative(type2),
77  tf.translate(Eigen::Vector3d(0.0001, 0, 0)),
78  test_type))
79  ->UseRealTime()
80  ->Unit(benchmark::TimeUnit::kMicrosecond);
81  }
82  }
83  }
84  }
85  // Not in collision. Within contact threshold
86  {
87  for (const auto& test_type : test_types)
88  {
89  // Loop over all primitive combinations
90  for (const auto& type1 : geometry_types)
91  {
92  for (const auto& type2 : geometry_types)
93  {
94  auto tf = Eigen::Isometry3d::Identity();
95  std::string name = "BM_CONTACT_TEST_1_" + checker->getName() + "_" +
96  ContactTestTypeStrings[static_cast<std::size_t>(test_type)] + "_" +
97  GeometryTypeStrings[static_cast<std::size_t>(type1)] + "_" +
98  GeometryTypeStrings[static_cast<std::size_t>(type2)];
99  benchmark::RegisterBenchmark(name.c_str(),
100  BM_CONTACT_TEST_FUNC,
101  DiscreteBenchmarkInfo(checker,
102  CreateUnitPrimative(type1),
103  Eigen::Isometry3d::Identity(),
104  CreateUnitPrimative(type2),
105  tf.translate(Eigen::Vector3d(0.6, 0, 0)),
106  test_type))
107  ->UseRealTime()
108  ->Unit(benchmark::TimeUnit::kMicrosecond);
109  }
110  }
111  }
112  }
113 
114  // Not in collision. Outside contact threshold
115  {
116  for (const auto& test_type : test_types)
117  {
118  // Loop over all primitive combinations
119  for (const auto& type1 : geometry_types)
120  {
121  for (const auto& type2 : geometry_types)
122  {
123  auto tf = Eigen::Isometry3d::Identity();
124  std::string name = "BM_CONTACT_TEST_2_" + checker->getName() + "_" +
125  ContactTestTypeStrings[static_cast<std::size_t>(test_type)] + "_" +
126  GeometryTypeStrings[static_cast<std::size_t>(type1)] + "_" +
127  GeometryTypeStrings[static_cast<std::size_t>(type2)];
128  benchmark::RegisterBenchmark(name.c_str(),
129  BM_CONTACT_TEST_FUNC,
130  DiscreteBenchmarkInfo(checker,
131  CreateUnitPrimative(type1),
132  Eigen::Isometry3d::Identity(),
133  CreateUnitPrimative(type2),
134  tf.translate(Eigen::Vector3d(2, 0, 0)),
135  test_type))
136  ->UseRealTime()
137  ->Unit(benchmark::TimeUnit::kMicrosecond);
138  }
139  }
140  }
141  }
142 
144  // setCollisionObjectTransform
146  {
147  std::function<void(benchmark::State&, int)> BM_SELECT_RANDOM_OBJECT_FUNC = BM_SELECT_RANDOM_OBJECT;
148  benchmark::RegisterBenchmark("BM_SELECT_RANDOM_OBJECT", BM_SELECT_RANDOM_OBJECT_FUNC, 256)
149  ->UseRealTime()
150  ->Unit(benchmark::TimeUnit::kNanosecond);
151  }
152  {
153  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE_FUNC =
155  std::vector<int> num_links = { 2, 4, 8, 16, 32, 64, 128, 256, 512 };
156 
157  for (const auto& num_link : num_links)
158  {
159  auto tf = Eigen::Isometry3d::Identity();
160  std::string name =
161  "BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
162  benchmark::RegisterBenchmark(name.c_str(),
163  BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE_FUNC,
164  DiscreteBenchmarkInfo(checker,
165  CreateUnitPrimative(GeometryType::BOX),
166  Eigen::Isometry3d::Identity(),
167  CreateUnitPrimative(GeometryType::BOX),
168  tf.translate(Eigen::Vector3d(2, 0, 0)),
170  num_link)
171  ->UseRealTime()
172  ->Unit(benchmark::TimeUnit::kNanosecond);
173  }
174  }
175  {
176  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR_FUNC =
178  std::vector<std::size_t> num_links = { 2, 4, 8, 16, 32, 64, 128, 256, 512 };
179 
180  for (const auto& num_link : num_links)
181  {
182  auto tf = Eigen::Isometry3d::Identity();
183  std::string name =
184  "BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
185  benchmark::RegisterBenchmark(name.c_str(),
186  BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR_FUNC,
187  DiscreteBenchmarkInfo(checker,
188  CreateUnitPrimative(GeometryType::BOX),
189  Eigen::Isometry3d::Identity(),
190  CreateUnitPrimative(GeometryType::BOX),
191  tf.translate(Eigen::Vector3d(2, 0, 0)),
193  num_link)
194  ->UseRealTime()
195  ->Unit(benchmark::TimeUnit::kNanosecond);
196  }
197  }
198  {
199  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP_FUNC =
201  std::vector<std::size_t> num_links = { 2, 4, 8, 16, 32, 64, 128, 256, 512 };
202 
203  for (const auto& num_link : num_links)
204  {
205  auto tf = Eigen::Isometry3d::Identity();
206  std::string name =
207  "BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
208  benchmark::RegisterBenchmark(name.c_str(),
209  BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP_FUNC,
210  DiscreteBenchmarkInfo(checker,
211  CreateUnitPrimative(GeometryType::BOX),
212  Eigen::Isometry3d::Identity(),
213  CreateUnitPrimative(GeometryType::BOX),
214  tf.translate(Eigen::Vector3d(2, 0, 0)),
216  num_link)
217  ->UseRealTime()
218  ->Unit(benchmark::TimeUnit::kNanosecond);
219  }
220  }
222  // Large Dataset contactTest
224  if (std::string(BENCHMARK_ARGS) != "CI_ONLY")
225  {
226  std::function<void(benchmark::State&, DiscreteContactManager::Ptr, int, tesseract_geometry::GeometryType)>
227  BM_LARGE_DATASET_MULTILINK_FUNC = BM_LARGE_DATASET_MULTILINK;
228  std::vector<int> edge_sizes = { 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12 };
229 
230  for (const auto& edge_size : edge_sizes)
231  {
232  DiscreteContactManager::Ptr clone = checker->clone();
233  std::string name =
234  "BM_LARGE_DATASET_MULTILINK_" + checker->getName() + "_CONVEX_MESH_EDGE_SIZE_" + std::to_string(edge_size);
235  benchmark::RegisterBenchmark(name.c_str(),
236  BM_LARGE_DATASET_MULTILINK_FUNC,
237  clone,
238  edge_size,
240  ->UseRealTime()
241  ->Unit(benchmark::TimeUnit::kNanosecond);
242  }
243  for (const auto& edge_size : edge_sizes)
244  {
245  DiscreteContactManager::Ptr clone = checker->clone();
246  std::string name =
247  "BM_LARGE_DATASET_MULTILINK_" + checker->getName() + "_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
248  benchmark::RegisterBenchmark(
249  name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
250  ->UseRealTime()
251  ->Unit(benchmark::TimeUnit::kNanosecond);
252  }
253  for (const auto& edge_size : edge_sizes)
254  {
255  DiscreteContactManager::Ptr clone = checker->clone();
256  std::string name =
257  "BM_LARGE_DATASET_MULTILINK_" + checker->getName() + "_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
258  benchmark::RegisterBenchmark(
259  name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::MESH)
260  ->UseRealTime()
261  ->Unit(benchmark::TimeUnit::kMillisecond);
262  }
263  std::function<void(benchmark::State&, DiscreteContactManager::Ptr, int, tesseract_geometry::GeometryType)>
264  BM_LARGE_DATASET_SINGLELINK_FUNC = BM_LARGE_DATASET_SINGLELINK;
265 
266  for (const auto& edge_size : edge_sizes)
267  {
268  DiscreteContactManager::Ptr clone = checker->clone();
269  std::string name =
270  "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() + "_CONVEX_MESH_EDGE_SIZE_" + std::to_string(edge_size);
271  benchmark::RegisterBenchmark(name.c_str(),
272  BM_LARGE_DATASET_SINGLELINK_FUNC,
273  clone,
274  edge_size,
276  ->UseRealTime()
277  ->Unit(benchmark::TimeUnit::kNanosecond);
278  }
279  for (const auto& edge_size : edge_sizes)
280  {
281  DiscreteContactManager::Ptr clone = checker->clone();
282  std::string name =
283  "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() + "_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
284  benchmark::RegisterBenchmark(
285  name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
286  ->UseRealTime()
287  ->Unit(benchmark::TimeUnit::kNanosecond);
288  }
289  for (const auto& edge_size : edge_sizes)
290  {
291  DiscreteContactManager::Ptr clone = checker->clone();
292  std::string name =
293  "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() + "_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
294  benchmark::RegisterBenchmark(
295  name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::MESH)
296  ->UseRealTime()
297  ->Unit(benchmark::TimeUnit::kMillisecond);
298  }
299  }
300 
301  benchmark::Initialize(&argc, argv);
302  benchmark::RunSpecifiedBenchmarks();
303 }
tesseract_collision::test_suite::BM_CLONE
static void BM_CLONE(benchmark::State &state, DiscreteBenchmarkInfo info, std::size_t num_obj)
Benchmark that checks the clone method in discrete contact managers.
Definition: primatives_benchmarks.hpp:42
tesseract_geometry::GeometryType
GeometryType
tesseract_collision::ContactTestType::LIMITED
@ LIMITED
tesseract_geometry::GeometryType::MESH
@ MESH
tesseract_collision::test_suite::BM_LARGE_DATASET_SINGLELINK
static void BM_LARGE_DATASET_SINGLELINK(benchmark::State &state, DiscreteContactManager::Ptr checker, int edge_size, tesseract_geometry::GeometryType type)
Benchmark that checks collisions between a lot of objects. In this case it is a grid of spheres in on...
Definition: large_dataset_benchmarks.hpp:110
large_dataset_benchmarks.hpp
main
int main(int argc, char **argv)
Definition: bullet_discrete_bvh_benchmarks.cpp:14
name
std::string name
tesseract_geometry::GeometryType::SPHERE
@ SPHERE
tesseract_collision::test_suite::DiscreteBenchmarkInfo
Contains the information necessary to run the benchmarks for discrete collision checking.
Definition: primatives_benchmarks.hpp:16
tesseract_collision::test_suite::BM_LARGE_DATASET_MULTILINK
static void BM_LARGE_DATASET_MULTILINK(benchmark::State &state, DiscreteContactManager::Ptr checker, int edge_size, tesseract_geometry::GeometryType type)
Benchmark that checks collisions between a lot of objects. In this case it is a grid of spheres - eac...
Definition: large_dataset_benchmarks.hpp:21
bullet_discrete_bvh_manager.h
Tesseract ROS Bullet discrete BVH collision manager.
primatives_benchmarks.hpp
tesseract_collision::tesseract_collision_bullet::BulletDiscreteBVHManager::ConstPtr
std::shared_ptr< const BulletDiscreteBVHManager > ConstPtr
Definition: bullet_discrete_bvh_manager.h:55
CreateUnitPrimative
tesseract_geometry::Geometry::Ptr CreateUnitPrimative(const tesseract_geometry::GeometryType type, const double scale=1.0)
Definition: benchmark_utils.hpp:12
geometry.h
tesseract_collision::ContactTestType::FIRST
@ FIRST
tesseract_collision::test_suite::BM_CONTACT_TEST
static void BM_CONTACT_TEST(benchmark::State &state, DiscreteBenchmarkInfo info)
Benchmark that checks the contactTest function in discrete contact managers.
Definition: primatives_benchmarks.hpp:62
tesseract_collision::test_suite::BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR
static void BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR(benchmark::State &state, DiscreteBenchmarkInfo info, std::size_t num_obj)
Benchmark that checks the setCollisionObjectsTransform(const std::vector<std::string>& names,...
Definition: primatives_benchmarks.hpp:118
tesseract_collision::test_suite::BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP
static void BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP(benchmark::State &state, DiscreteBenchmarkInfo info, std::size_t num_obj)
Benchmark that checks the setCollisionObjectsTransform(const tesseract_common::TransformMap& transfor...
Definition: primatives_benchmarks.hpp:146
tesseract_geometry
tesseract_collision::test_suite::BM_SELECT_RANDOM_OBJECT
static void BM_SELECT_RANDOM_OBJECT(benchmark::State &state, int num_obj)
Benchmark that checks how long it takes to select a random object so that number can be subtracted fr...
Definition: primatives_benchmarks.hpp:80
tesseract_collision
Definition: bullet_cast_bvh_manager.h:48
tesseract_geometry::GeometryType::CONVEX_MESH
@ CONVEX_MESH
tesseract_collision::ContactTestType::ALL
@ ALL
tesseract_collision::ContactTestTypeStrings
static const std::vector< std::string > ContactTestTypeStrings
Definition: types.h:74
tesseract_collision::test_suite::BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE
static void BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE(benchmark::State &state, DiscreteBenchmarkInfo info, std::size_t num_obj)
Benchmark that checks the setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry...
Definition: primatives_benchmarks.hpp:91
tesseract_collision::DiscreteContactManager::Ptr
std::shared_ptr< DiscreteContactManager > Ptr
Definition: discrete_contact_manager.h:48
tesseract_collision::ContactTestType::CLOSEST
@ CLOSEST
benchmark_utils.hpp


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