bullet_discrete_simple_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::BulletDiscreteSimpleManager>();
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  // BulletDiscreteSimpleManager - 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  std::string name = "BM_CONTACT_TEST_0_" + checker->getName() + "_" +
67  ContactTestTypeStrings[static_cast<std::size_t>(test_type)] + "_" +
68  GeometryTypeStrings[static_cast<std::size_t>(type1)] + "_" +
69  GeometryTypeStrings[static_cast<std::size_t>(type2)];
70  benchmark::RegisterBenchmark(name.c_str(),
71  BM_CONTACT_TEST_FUNC,
72  DiscreteBenchmarkInfo(checker,
73  CreateUnitPrimative(type1),
74  Eigen::Isometry3d::Identity(),
75  CreateUnitPrimative(type2),
76  Eigen::Isometry3d::Identity(),
77  test_type))
78  ->UseRealTime()
79  ->Unit(benchmark::TimeUnit::kMicrosecond);
80  }
81  }
82  }
83  }
84  // BulletDiscreteSimpleManager - Not in collision. Within contact threshold
85  {
86  for (const auto& test_type : test_types)
87  {
88  // Loop over all primitive combinations
89  for (const auto& type1 : geometry_types)
90  {
91  for (const auto& type2 : geometry_types)
92  {
93  auto tf = Eigen::Isometry3d::Identity();
94  std::string name = "BM_CONTACT_TEST_1_" + checker->getName() + "_" +
95  ContactTestTypeStrings[static_cast<std::size_t>(test_type)] + "_" +
96  GeometryTypeStrings[static_cast<std::size_t>(type1)] + "_" +
97  GeometryTypeStrings[static_cast<std::size_t>(type2)];
98  benchmark::RegisterBenchmark(name.c_str(),
99  BM_CONTACT_TEST_FUNC,
100  DiscreteBenchmarkInfo(checker,
101  CreateUnitPrimative(type1),
102  Eigen::Isometry3d::Identity(),
103  CreateUnitPrimative(type2),
104  tf.translate(Eigen::Vector3d(0.6, 0, 0)),
105  test_type))
106  ->UseRealTime()
107  ->Unit(benchmark::TimeUnit::kMicrosecond);
108  }
109  }
110  }
111  }
112 
113  // BulletDiscreteSimpleManager - Not in collision. Outside contact threshold
114  {
115  for (const auto& test_type : test_types)
116  {
117  // Loop over all primitive combinations
118  for (const auto& type1 : geometry_types)
119  {
120  for (const auto& type2 : geometry_types)
121  {
122  auto tf = Eigen::Isometry3d::Identity();
123  std::string name = "BM_CONTACT_TEST_2_" + checker->getName() + "_" +
124  ContactTestTypeStrings[static_cast<std::size_t>(test_type)] + "_" +
125  GeometryTypeStrings[static_cast<std::size_t>(type1)] + "_" +
126  GeometryTypeStrings[static_cast<std::size_t>(type2)];
127  benchmark::RegisterBenchmark(name.c_str(),
128  BM_CONTACT_TEST_FUNC,
129  DiscreteBenchmarkInfo(checker,
130  CreateUnitPrimative(type1),
131  Eigen::Isometry3d::Identity(),
132  CreateUnitPrimative(type2),
133  tf.translate(Eigen::Vector3d(2, 0, 0)),
134  test_type))
135  ->UseRealTime()
136  ->Unit(benchmark::TimeUnit::kMicrosecond);
137  }
138  }
139  }
140  }
141 
143  // setCollisionObjectTransform
145  {
146  std::function<void(benchmark::State&, int)> BM_SELECT_RANDOM_OBJECT_FUNC = BM_SELECT_RANDOM_OBJECT;
147  benchmark::RegisterBenchmark("BM_SELECT_RANDOM_OBJECT", BM_SELECT_RANDOM_OBJECT_FUNC, 256)
148  ->UseRealTime()
149  ->Unit(benchmark::TimeUnit::kNanosecond);
150  }
151  {
152  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE_FUNC =
154  std::vector<int> num_links = { 2, 4, 8, 16, 32, 64, 128, 256, 512 };
155 
156  for (const auto& num_link : num_links)
157  {
158  auto tf = Eigen::Isometry3d::Identity();
159  std::string name =
160  "BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
161  benchmark::RegisterBenchmark(name.c_str(),
162  BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE_FUNC,
163  DiscreteBenchmarkInfo(checker,
164  CreateUnitPrimative(GeometryType::BOX),
165  Eigen::Isometry3d::Identity(),
166  CreateUnitPrimative(GeometryType::BOX),
167  tf.translate(Eigen::Vector3d(2, 0, 0)),
169  num_link)
170  ->UseRealTime()
171  ->Unit(benchmark::TimeUnit::kNanosecond);
172  }
173  }
174  {
175  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR_FUNC =
177  std::vector<std::size_t> num_links = { 2, 4, 8, 16, 32, 64, 128, 256, 512 };
178 
179  for (const auto& num_link : num_links)
180  {
181  auto tf = Eigen::Isometry3d::Identity();
182  std::string name =
183  "BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
184  benchmark::RegisterBenchmark(name.c_str(),
185  BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR_FUNC,
186  DiscreteBenchmarkInfo(checker,
187  CreateUnitPrimative(GeometryType::BOX),
188  Eigen::Isometry3d::Identity(),
189  CreateUnitPrimative(GeometryType::BOX),
190  tf.translate(Eigen::Vector3d(2, 0, 0)),
192  num_link)
193  ->UseRealTime()
194  ->Unit(benchmark::TimeUnit::kNanosecond);
195  }
196  }
197  {
198  std::function<void(benchmark::State&, DiscreteBenchmarkInfo, int)> BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP_FUNC =
200  std::vector<std::size_t> num_links = { 2, 4, 8, 16, 32, 64, 128, 256, 512 };
201 
202  for (const auto& num_link : num_links)
203  {
204  auto tf = Eigen::Isometry3d::Identity();
205  std::string name =
206  "BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP_" + checker->getName() + "_ACTIVE_OBJ_" + std::to_string(num_link);
207  benchmark::RegisterBenchmark(name.c_str(),
208  BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP_FUNC,
209  DiscreteBenchmarkInfo(checker,
210  CreateUnitPrimative(GeometryType::BOX),
211  Eigen::Isometry3d::Identity(),
212  CreateUnitPrimative(GeometryType::BOX),
213  tf.translate(Eigen::Vector3d(2, 0, 0)),
215  num_link)
216  ->UseRealTime()
217  ->Unit(benchmark::TimeUnit::kNanosecond);
218  }
219  }
221  // Large Dataset contactTest
223  if (std::string(BENCHMARK_ARGS) != "CI_ONLY")
224  {
225  std::function<void(benchmark::State&, DiscreteContactManager::Ptr, int, tesseract_geometry::GeometryType)>
226  BM_LARGE_DATASET_MULTILINK_FUNC = BM_LARGE_DATASET_MULTILINK;
227  std::vector<int> edge_sizes = { 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12 };
228 
229  for (const auto& edge_size : edge_sizes)
230  {
231  DiscreteContactManager::Ptr clone = checker->clone();
232  std::string name =
233  "BM_LARGE_DATASET_MULTILINK_" + checker->getName() + "_CONVEX_MESH_EDGE_SIZE_" + std::to_string(edge_size);
234  benchmark::RegisterBenchmark(name.c_str(),
235  BM_LARGE_DATASET_MULTILINK_FUNC,
236  clone,
237  edge_size,
239  ->UseRealTime()
240  ->Unit(benchmark::TimeUnit::kNanosecond);
241  }
242  for (const auto& edge_size : edge_sizes)
243  {
244  DiscreteContactManager::Ptr clone = checker->clone();
245  std::string name =
246  "BM_LARGE_DATASET_MULTILINK_" + checker->getName() + "_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
247  benchmark::RegisterBenchmark(
248  name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
249  ->UseRealTime()
250  ->Unit(benchmark::TimeUnit::kNanosecond);
251  }
252  for (const auto& edge_size : edge_sizes)
253  {
254  DiscreteContactManager::Ptr clone = checker->clone();
255  std::string name =
256  "BM_LARGE_DATASET_MULTILINK_" + checker->getName() + "_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
257  benchmark::RegisterBenchmark(
258  name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::MESH)
259  ->UseRealTime()
260  ->Unit(benchmark::TimeUnit::kMillisecond);
261  }
262  std::function<void(benchmark::State&, DiscreteContactManager::Ptr, int, tesseract_geometry::GeometryType)>
263  BM_LARGE_DATASET_SINGLELINK_FUNC = BM_LARGE_DATASET_SINGLELINK;
264 
265  for (const auto& edge_size : edge_sizes)
266  {
267  DiscreteContactManager::Ptr clone = checker->clone();
268  std::string name =
269  "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() + "_CONVEX_MESH_EDGE_SIZE_" + std::to_string(edge_size);
270  benchmark::RegisterBenchmark(name.c_str(),
271  BM_LARGE_DATASET_SINGLELINK_FUNC,
272  clone,
273  edge_size,
275  ->UseRealTime()
276  ->Unit(benchmark::TimeUnit::kNanosecond);
277  }
278  for (const auto& edge_size : edge_sizes)
279  {
280  DiscreteContactManager::Ptr clone = checker->clone();
281  std::string name =
282  "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() + "_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
283  benchmark::RegisterBenchmark(
284  name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
285  ->UseRealTime()
286  ->Unit(benchmark::TimeUnit::kNanosecond);
287  }
288  for (const auto& edge_size : edge_sizes)
289  {
290  DiscreteContactManager::Ptr clone = checker->clone();
291  std::string name =
292  "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() + "_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
293  benchmark::RegisterBenchmark(
294  name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::MESH)
295  ->UseRealTime()
296  ->Unit(benchmark::TimeUnit::kMillisecond);
297  }
298  }
299 
300  benchmark::Initialize(&argc, argv);
301  benchmark::RunSpecifiedBenchmarks();
302 }
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
bullet_discrete_simple_manager.h
Tesseract ROS Bullet discrete simple collision manager.
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
tesseract_collision::tesseract_collision_bullet::BulletDiscreteSimpleManager::ConstPtr
std::shared_ptr< const BulletDiscreteSimpleManager > ConstPtr
Definition: bullet_discrete_simple_manager.h:55
large_dataset_benchmarks.hpp
main
int main(int argc, char **argv)
Definition: bullet_discrete_simple_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
primatives_benchmarks.hpp
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