1 #include <benchmark/benchmark.h>
11 using namespace test_suite;
14 int main(
int argc,
char** argv)
17 std::make_shared<tesseract_collision_bullet::BulletDiscreteSimpleManager>();
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 std::string
name =
"BM_CONTACT_TEST_0_" + checker->getName() +
"_" +
68 GeometryTypeStrings[
static_cast<std::size_t
>(type1)] +
"_" +
69 GeometryTypeStrings[
static_cast<std::size_t
>(type2)];
70 benchmark::RegisterBenchmark(
name.c_str(),
74 Eigen::Isometry3d::Identity(),
76 Eigen::Isometry3d::Identity(),
79 ->Unit(benchmark::TimeUnit::kMicrosecond);
86 for (
const auto& test_type : test_types)
89 for (
const auto& type1 : geometry_types)
91 for (
const auto& type2 : geometry_types)
93 auto tf = Eigen::Isometry3d::Identity();
94 std::string
name =
"BM_CONTACT_TEST_1_" + checker->getName() +
"_" +
96 GeometryTypeStrings[
static_cast<std::size_t
>(type1)] +
"_" +
97 GeometryTypeStrings[
static_cast<std::size_t
>(type2)];
98 benchmark::RegisterBenchmark(
name.c_str(),
102 Eigen::Isometry3d::Identity(),
104 tf.translate(Eigen::Vector3d(0.6, 0, 0)),
107 ->Unit(benchmark::TimeUnit::kMicrosecond);
115 for (
const auto& test_type : test_types)
118 for (
const auto& type1 : geometry_types)
120 for (
const auto& type2 : geometry_types)
122 auto tf = Eigen::Isometry3d::Identity();
123 std::string
name =
"BM_CONTACT_TEST_2_" + checker->getName() +
"_" +
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,
131 Eigen::Isometry3d::Identity(),
133 tf.translate(Eigen::Vector3d(2, 0, 0)),
136 ->Unit(benchmark::TimeUnit::kMicrosecond);
147 benchmark::RegisterBenchmark(
"BM_SELECT_RANDOM_OBJECT", BM_SELECT_RANDOM_OBJECT_FUNC, 256)
149 ->Unit(benchmark::TimeUnit::kNanosecond);
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 };
156 for (
const auto& num_link : num_links)
158 auto tf = Eigen::Isometry3d::Identity();
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,
165 Eigen::Isometry3d::Identity(),
167 tf.translate(Eigen::Vector3d(2, 0, 0)),
171 ->Unit(benchmark::TimeUnit::kNanosecond);
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 };
179 for (
const auto& num_link : num_links)
181 auto tf = Eigen::Isometry3d::Identity();
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,
188 Eigen::Isometry3d::Identity(),
190 tf.translate(Eigen::Vector3d(2, 0, 0)),
194 ->Unit(benchmark::TimeUnit::kNanosecond);
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 };
202 for (
const auto& num_link : num_links)
204 auto tf = Eigen::Isometry3d::Identity();
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,
211 Eigen::Isometry3d::Identity(),
213 tf.translate(Eigen::Vector3d(2, 0, 0)),
217 ->Unit(benchmark::TimeUnit::kNanosecond);
223 if (std::string(BENCHMARK_ARGS) !=
"CI_ONLY")
227 std::vector<int> edge_sizes = { 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12 };
229 for (
const auto& edge_size : edge_sizes)
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,
240 ->Unit(benchmark::TimeUnit::kNanosecond);
242 for (
const auto& edge_size : edge_sizes)
246 "BM_LARGE_DATASET_MULTILINK_" + checker->getName() +
"_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
247 benchmark::RegisterBenchmark(
250 ->Unit(benchmark::TimeUnit::kNanosecond);
252 for (
const auto& edge_size : edge_sizes)
256 "BM_LARGE_DATASET_MULTILINK_" + checker->getName() +
"_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
257 benchmark::RegisterBenchmark(
260 ->Unit(benchmark::TimeUnit::kMillisecond);
265 for (
const auto& edge_size : edge_sizes)
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,
276 ->Unit(benchmark::TimeUnit::kNanosecond);
278 for (
const auto& edge_size : edge_sizes)
282 "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() +
"_PRIMATIVE_EDGE_SIZE_" + std::to_string(edge_size);
283 benchmark::RegisterBenchmark(
286 ->Unit(benchmark::TimeUnit::kNanosecond);
288 for (
const auto& edge_size : edge_sizes)
292 "BM_LARGE_DATASET_SINGLELINK_" + checker->getName() +
"_DETAILED_MESH_EDGE_SIZE_" + std::to_string(edge_size);
293 benchmark::RegisterBenchmark(
296 ->Unit(benchmark::TimeUnit::kMillisecond);
300 benchmark::Initialize(&argc, argv);
301 benchmark::RunSpecifiedBenchmarks();