1 #include <benchmark/benchmark.h>
11 using namespace test_suite;
14 int main(
int argc,
char** argv)
17 std::make_shared<tesseract_collision_bullet::BulletDiscreteBVHManager>();
24 std::vector<int> num_links = { 0, 2, 4, 8, 16, 32, 64, 128, 256, 512 };
26 for (
const auto& num_link : num_links)
28 std::string
name =
"BM_CLONE_" + checker->getName() +
"_ACTIVE_OBJ_" + std::to_string(num_link);
29 benchmark::RegisterBenchmark(
name.c_str(),
33 Eigen::Isometry3d::Identity(),
35 Eigen::Isometry3d::Identity(),
39 ->Unit(benchmark::TimeUnit::kMicrosecond);
49 std::vector<tesseract_geometry::GeometryType> geometry_types = {
50 GeometryType::BOX, GeometryType::CONE, GeometryType::SPHERE, GeometryType::CAPSULE, GeometryType::CYLINDER
53 std::vector<ContactTestType> test_types = {
59 for (
const auto& test_type : test_types)
62 for (
const auto& type1 : geometry_types)
64 for (
const auto& type2 : geometry_types)
66 auto tf = Eigen::Isometry3d::Identity();
67 std::string
name =
"BM_CONTACT_TEST_0_" + checker->getName() +
"_" +
69 GeometryTypeStrings[
static_cast<std::size_t
>(type1)] +
"_" +
70 GeometryTypeStrings[
static_cast<std::size_t
>(type2)];
71 benchmark::RegisterBenchmark(
name.c_str(),
75 Eigen::Isometry3d::Identity(),
77 tf.translate(Eigen::Vector3d(0.0001, 0, 0)),
80 ->Unit(benchmark::TimeUnit::kMicrosecond);
87 for (
const auto& test_type : test_types)
90 for (
const auto& type1 : geometry_types)
92 for (
const auto& type2 : geometry_types)
94 auto tf = Eigen::Isometry3d::Identity();
95 std::string
name =
"BM_CONTACT_TEST_1_" + checker->getName() +
"_" +
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,
103 Eigen::Isometry3d::Identity(),
105 tf.translate(Eigen::Vector3d(0.6, 0, 0)),
108 ->Unit(benchmark::TimeUnit::kMicrosecond);
116 for (
const auto& test_type : test_types)
119 for (
const auto& type1 : geometry_types)
121 for (
const auto& type2 : geometry_types)
123 auto tf = Eigen::Isometry3d::Identity();
124 std::string
name =
"BM_CONTACT_TEST_2_" + checker->getName() +
"_" +
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,
132 Eigen::Isometry3d::Identity(),
134 tf.translate(Eigen::Vector3d(2, 0, 0)),
137 ->Unit(benchmark::TimeUnit::kMicrosecond);
148 benchmark::RegisterBenchmark(
"BM_SELECT_RANDOM_OBJECT", BM_SELECT_RANDOM_OBJECT_FUNC, 256)
150 ->Unit(benchmark::TimeUnit::kNanosecond);
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 };
157 for (
const auto& num_link : num_links)
159 auto tf = Eigen::Isometry3d::Identity();
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,
166 Eigen::Isometry3d::Identity(),
168 tf.translate(Eigen::Vector3d(2, 0, 0)),
172 ->Unit(benchmark::TimeUnit::kNanosecond);
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 };
180 for (
const auto& num_link : num_links)
182 auto tf = Eigen::Isometry3d::Identity();
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,
189 Eigen::Isometry3d::Identity(),
191 tf.translate(Eigen::Vector3d(2, 0, 0)),
195 ->Unit(benchmark::TimeUnit::kNanosecond);
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 };
203 for (
const auto& num_link : num_links)
205 auto tf = Eigen::Isometry3d::Identity();
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,
212 Eigen::Isometry3d::Identity(),
214 tf.translate(Eigen::Vector3d(2, 0, 0)),
218 ->Unit(benchmark::TimeUnit::kNanosecond);
224 if (std::string(BENCHMARK_ARGS) !=
"CI_ONLY")
228 std::vector<int> edge_sizes = { 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12 };
230 for (
const auto& edge_size : edge_sizes)
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,
241 ->Unit(benchmark::TimeUnit::kNanosecond);
243 for (
const auto& edge_size : edge_sizes)
247 "BM_LARGE_DATASET_MULTILINK_" + checker->getName() +
"_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
248 benchmark::RegisterBenchmark(
251 ->Unit(benchmark::TimeUnit::kNanosecond);
253 for (
const auto& edge_size : edge_sizes)
257 "BM_LARGE_DATASET_MULTILINK_" + checker->getName() +
"_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
258 benchmark::RegisterBenchmark(
261 ->Unit(benchmark::TimeUnit::kMillisecond);
266 for (
const auto& edge_size : edge_sizes)
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,
277 ->Unit(benchmark::TimeUnit::kNanosecond);
279 for (
const auto& edge_size : edge_sizes)
283 "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() +
"_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
284 benchmark::RegisterBenchmark(
287 ->Unit(benchmark::TimeUnit::kNanosecond);
289 for (
const auto& edge_size : edge_sizes)
293 "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() +
"_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
294 benchmark::RegisterBenchmark(
297 ->Unit(benchmark::TimeUnit::kMillisecond);
301 benchmark::Initialize(&argc, argv);
302 benchmark::RunSpecifiedBenchmarks();