Skip to content

Commit

Permalink
Update tesseract_collision benchmarks (#868)
Browse files Browse the repository at this point in the history
  • Loading branch information
Levi-Armstrong authored Mar 21, 2023
1 parent dd348a9 commit 729d339
Show file tree
Hide file tree
Showing 6 changed files with 22 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -38,5 +38,5 @@ inline tesseract_geometry::Geometry::Ptr CreateUnitPrimative(const tesseract_geo
break;
}
return geom;
};
}
#endif
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ static void BM_CLONE(benchmark::State& state, DiscreteBenchmarkInfo info, std::s
{
benchmark::DoNotOptimize(clone = info.contact_manager_->clone());
}
};
}

/** @brief Benchmark that checks the contactTest function in discrete contact managers*/
static void BM_CONTACT_TEST(benchmark::State& state, DiscreteBenchmarkInfo info) // NOLINT
Expand All @@ -73,7 +73,7 @@ static void BM_CONTACT_TEST(benchmark::State& state, DiscreteBenchmarkInfo info)
result.clear();
info.contact_manager_->contactTest(result, ContactRequest(info.contact_test_type_));
}
};
}

/** @brief Benchmark that checks how long it takes to select a random object so that number can be subtracted from other
* benchmarks if that is important*/
Expand All @@ -84,7 +84,7 @@ static void BM_SELECT_RANDOM_OBJECT(benchmark::State& state, int num_obj)
{
benchmark::DoNotOptimize(selected_link = rand() % num_obj); // NOLINT
}
};
}

/** @brief Benchmark that checks the setCollisionObjectsTransform(const std::string& name, const Eigen::Isometry3d&
* pose) method in discrete contact managers*/
Expand All @@ -111,7 +111,7 @@ static void BM_SET_COLLISION_OBJECTS_TRANSFORM_SINGLE(benchmark::State& state,
std::size_t selected_link = static_cast<std::size_t>(rand()) % num_obj;
info.contact_manager_->setCollisionObjectsTransform(active_obj[selected_link], info.obj2_poses[0]);
}
};
}

/** @brief Benchmark that checks the setCollisionObjectsTransform(const std::vector<std::string>& names, const
tesseract_common::VectorIsometry3d& poses) method in discrete contact managers. Moves only a single random link*/
Expand Down Expand Up @@ -139,7 +139,7 @@ static void BM_SET_COLLISION_OBJECTS_TRANSFORM_VECTOR(benchmark::State& state,
selected_links[0] = active_obj[static_cast<std::size_t>(rand()) % num_obj];
info.contact_manager_->setCollisionObjectsTransform(selected_links, info.obj2_poses);
}
};
}

/** @brief Benchmark that checks the setCollisionObjectsTransform(const tesseract_common::TransformMap& transforms)
* method in discrete contact managers. Moves only a single random link*/
Expand All @@ -163,10 +163,11 @@ static void BM_SET_COLLISION_OBJECTS_TRANSFORM_MAP(benchmark::State& state,
{
// Including this seems necessary to insure that a distribution of links is used rather than always searching for
// the same one. It might be worth it to manually time these as well if it's really important
selected_link.clear(); // Need to clear or this grows and is not releastic to compare to vector version
selected_link[active_obj[static_cast<std::size_t>(rand()) % num_obj]] = info.obj2_poses[0];
info.contact_manager_->setCollisionObjectsTransform(selected_link);
}
};
}

} // namespace test_suite
} // namespace tesseract_collision
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -234,7 +234,7 @@ int main(int argc, char** argv)
edge_size,
tesseract_geometry::GeometryType::CONVEX_MESH)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -244,7 +244,7 @@ int main(int argc, char** argv)
benchmark::RegisterBenchmark(
name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -270,7 +270,7 @@ int main(int argc, char** argv)
edge_size,
tesseract_geometry::GeometryType::CONVEX_MESH)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -280,7 +280,7 @@ int main(int argc, char** argv)
benchmark::RegisterBenchmark(
name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ int main(int argc, char** argv)
edge_size,
tesseract_geometry::GeometryType::CONVEX_MESH)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -243,7 +243,7 @@ int main(int argc, char** argv)
benchmark::RegisterBenchmark(
name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -269,7 +269,7 @@ int main(int argc, char** argv)
edge_size,
tesseract_geometry::GeometryType::CONVEX_MESH)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -279,7 +279,7 @@ int main(int argc, char** argv)
benchmark::RegisterBenchmark(
name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand Down
2 changes: 2 additions & 0 deletions tesseract_collision/test/benchmarks/collision_profile.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,8 @@ TESSERACT_COMMON_IGNORE_WARNINGS_POP
#include <tesseract_collision/bullet/convex_hull_utils.h>
#include <tesseract_collision/fcl/fcl_discrete_managers.h>

#include <tesseract_geometry/impl/sphere.h>

static const std::size_t DIM = 10;

using namespace tesseract_collision;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ int main(int argc, char** argv)
edge_size,
tesseract_geometry::GeometryType::CONVEX_MESH)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -253,7 +253,7 @@ int main(int argc, char** argv)
benchmark::RegisterBenchmark(
name.c_str(), BM_LARGE_DATASET_MULTILINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
// These last two took 45s and 120s. Too long to run in CI, and impractical for our purposes anyway.
if (RUN_QUICK)
Expand Down Expand Up @@ -285,7 +285,7 @@ int main(int argc, char** argv)
edge_size,
tesseract_geometry::GeometryType::CONVEX_MESH)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand All @@ -295,7 +295,7 @@ int main(int argc, char** argv)
benchmark::RegisterBenchmark(
name.c_str(), BM_LARGE_DATASET_SINGLELINK_FUNC, clone, edge_size, tesseract_geometry::GeometryType::SPHERE)
->UseRealTime()
->Unit(benchmark::TimeUnit::kMillisecond);
->Unit(benchmark::TimeUnit::kNanosecond);
}
for (const auto& edge_size : edge_sizes)
{
Expand Down

0 comments on commit 729d339

Please sign in to comment.