Skip to content

Commit

Permalink
make tbb and pcl optional for benchmark (#17)
Browse files Browse the repository at this point in the history
  • Loading branch information
koide3 authored Apr 8, 2024
1 parent d09f920 commit 75a1ad3
Show file tree
Hide file tree
Showing 3 changed files with 78 additions and 56 deletions.
30 changes: 14 additions & 16 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,10 @@ option(BUILD_WITH_MARCH_NATIVE "Build with -march=native" OFF)
# Set mandatory dependencies of optional features
if(BUILD_TESTS OR BUILD_EXAMPLES OR BUILD_BENCHMARKS)
find_package(fmt REQUIRED)
set(BUILD_HELPER ON CACHE BOOL "Helper library is required" FORCE)
set(BUILD_WITH_TBB ON CACHE BOOL "TBB is required" FORCE)
endif()
if(BUILD_TESTS OR BUILD_EXAMPLES)
set(BUILD_HELPER ON CACHE BOOL "Helper library is required" FORCE)
set(BUILD_WITH_TBB ON CACHE BOOL "TBB is required" FORCE)
set(BUILD_WITH_PCL ON CACHE BOOL "PCL is required" FORCE)
endif()

Expand Down Expand Up @@ -176,20 +176,18 @@ if(BUILD_BENCHMARKS)
$<TARGET_NAME_IF_EXISTS:TBB::tbbmalloc>
)

if(BUILD_WITH_PCL)
# Downsampling benchmark
add_executable(downsampling_benchmark
src/benchmark/downsampling_benchmark.cpp
)
target_link_libraries(downsampling_benchmark PRIVATE
fmt::fmt
Eigen3::Eigen
$<TARGET_NAME_IF_EXISTS:OpenMP::OpenMP_CXX>
$<TARGET_NAME_IF_EXISTS:TBB::tbb>
$<TARGET_NAME_IF_EXISTS:TBB::tbbmalloc>
PCL::PCL
)
endif()
# Downsampling benchmark
add_executable(downsampling_benchmark
src/benchmark/downsampling_benchmark.cpp
)
target_link_libraries(downsampling_benchmark PRIVATE
fmt::fmt
Eigen3::Eigen
$<TARGET_NAME_IF_EXISTS:OpenMP::OpenMP_CXX>
$<TARGET_NAME_IF_EXISTS:TBB::tbb>
$<TARGET_NAME_IF_EXISTS:TBB::tbbmalloc>
$<TARGET_NAME_IF_EXISTS:PCL::PCL>
)
endif()

#############
Expand Down
52 changes: 33 additions & 19 deletions src/benchmark/downsampling_benchmark.cpp
Original file line number Diff line number Diff line change
@@ -1,19 +1,21 @@
#include <fmt/format.h>

#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/approximate_voxel_grid.h>

#include <small_gicp/util/downsampling.hpp>
#include <small_gicp/util/downsampling_omp.hpp>
#ifdef BUILD_WITH_TBB
#include <small_gicp/util/downsampling_tbb.hpp>
#endif
#include <small_gicp/points/point_cloud.hpp>
#include <small_gicp/benchmark/benchmark.hpp>

#ifdef BUILD_WITH_PCL
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/approximate_voxel_grid.h>
#include <small_gicp/pcl/pcl_point.hpp>
#include <small_gicp/pcl/pcl_point_traits.hpp>
#include <small_gicp/benchmark/benchmark.hpp>
#endif

namespace small_gicp {

Expand All @@ -35,6 +37,7 @@ void benchmark(const std::vector<PointCloudPtr>& raw_points, double leaf_size, c
std::cout << fmt::format("{} [msec/scan] {} [points]", times.str(), num_points.str()) << std::endl;
}

#ifdef BUILD_WITH_PCL
template <typename VoxelGrid, typename PointCloudPtr>
auto downsample_pcl(const PointCloudPtr& points, double leaf_size) {
VoxelGrid voxelgrid;
Expand All @@ -45,6 +48,7 @@ auto downsample_pcl(const PointCloudPtr& points, double leaf_size) {
voxelgrid.filter(*downsampled);
return downsampled;
}
#endif

} // namespace small_gicp

Expand Down Expand Up @@ -85,38 +89,48 @@ int main(int argc, char** argv) {
std::cout << "num_frames=" << kitti.points.size() << std::endl;
std::cout << fmt::format("num_points={} [points]", summarize(kitti.points, [](const auto& pts) { return pts.size(); })) << std::endl;

const auto points_pcl = kitti.convert<pcl::PointCloud<pcl::PointXYZ>>(true);
#ifdef BUILD_WITH_PCL
const auto points = kitti.convert<pcl::PointCloud<pcl::PointXYZ>>(true);
#else
const auto points = kitti.convert<PointCloud>(true);
#endif

// Warming up
std::cout << "---" << std::endl;
std::cout << "leaf_size=0.5(warmup)" << std::endl;
#ifdef BUILD_WITH_PCL
std::cout << fmt::format("{:25}: ", "pcl_voxelgrid") << std::flush;
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::VoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
benchmark(points, 0.5, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::VoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
std::cout << fmt::format("{:25}: ", "pcl_approx_voxelgrid") << std::flush;
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::ApproximateVoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
benchmark(points, 0.5, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::ApproximateVoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
#endif
std::cout << fmt::format("{:25}: ", "small_voxelgrid") << std::flush;
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return voxelgrid_sampling(*points, leaf_size); });
benchmark(points, 0.5, [](const auto& points, double leaf_size) { return voxelgrid_sampling(*points, leaf_size); });
std::cout << fmt::format("{:25}: ", "small_voxelgrid_omp") << std::flush;
benchmark(points, 0.5, [=](const auto& points, double leaf_size) { return voxelgrid_sampling_omp(*points, leaf_size, num_threads); });
#ifdef BUILD_WITH_TBB
std::cout << fmt::format("{:25}: ", "small_voxelgrid_tbb") << std::flush;
benchmark(points_pcl, 0.5, [](const auto& points, double leaf_size) { return voxelgrid_sampling_tbb(*points, leaf_size); });
benchmark(points, 0.5, [](const auto& points, double leaf_size) { return voxelgrid_sampling_tbb(*points, leaf_size); });
#endif
std::cout << fmt::format("{:25}: ", "small_voxelgrid_omp") << std::flush;
benchmark(points_pcl, 0.5, [=](const auto& points, double leaf_size) { return voxelgrid_sampling_omp(*points, leaf_size, num_threads); });

// Benchmark
for (double leaf_size = 0.1; leaf_size <= 1.51; leaf_size += 0.1) {
std::cout << "---" << std::endl;
std::cout << "leaf_size=" << leaf_size << std::endl;
#ifdef BUILD_WITH_PCL
std::cout << fmt::format("{:25}: ", "pcl_voxelgrid") << std::flush;
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::VoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
benchmark(points, leaf_size, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::VoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
std::cout << fmt::format("{:25}: ", "pcl_approx_voxelgrid") << std::flush;
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::ApproximateVoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
benchmark(points, leaf_size, [](const auto& points, double leaf_size) { return downsample_pcl<pcl::ApproximateVoxelGrid<pcl::PointXYZ>>(points, leaf_size); });
#endif
std::cout << fmt::format("{:25}: ", "small_voxelgrid") << std::flush;
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return voxelgrid_sampling(*points, leaf_size); });
benchmark(points, leaf_size, [](const auto& points, double leaf_size) { return voxelgrid_sampling(*points, leaf_size); });
std::cout << fmt::format("{:25}: ", "small_voxelgrid_omp") << std::flush;
benchmark(points, leaf_size, [=](const auto& points, double leaf_size) { return voxelgrid_sampling_omp(*points, leaf_size, num_threads); });
#ifdef BUILD_WITH_TBB
std::cout << fmt::format("{:25}: ", "small_voxelgrid_tbb") << std::flush;
benchmark(points_pcl, leaf_size, [](const auto& points, double leaf_size) { return voxelgrid_sampling_tbb(*points, leaf_size); });
benchmark(points, leaf_size, [](const auto& points, double leaf_size) { return voxelgrid_sampling_tbb(*points, leaf_size); });
#endif
std::cout << fmt::format("{:25}: ", "small_voxelgrid_omp") << std::flush;
benchmark(points_pcl, leaf_size, [=](const auto& points, double leaf_size) { return voxelgrid_sampling_omp(*points, leaf_size, num_threads); });
}

return 0;
Expand Down
52 changes: 31 additions & 21 deletions src/benchmark/kdtree_benchmark.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,21 @@
#include <small_gicp/points/point_cloud.hpp>
#include <small_gicp/ann/kdtree.hpp>
#include <small_gicp/ann/kdtree_omp.hpp>
#include <small_gicp/ann/kdtree_tbb.hpp>
#include <small_gicp/util/downsampling.hpp>
#include <small_gicp/util/downsampling_tbb.hpp>
#include <small_gicp/benchmark/benchmark.hpp>

#ifdef BUILD_WITH_TBB
#include <small_gicp/ann/kdtree_tbb.hpp>
#endif

int main(int argc, char** argv) {
using namespace small_gicp;

if (argc < 2) {
std::cout << "USAGE: kdtree_benchmark <dataset_path>" << std::endl;
std::cout << "OPTIONS:" << std::endl;
std::cout << " --num_threads <value> (default: 4)" << std::endl;
std::cout << " --method <str> (small|tbb|omp)" << std::endl;
std::cout << " --method <str> (small|omp|tbb)" << std::endl;
return 0;
}

Expand Down Expand Up @@ -43,30 +45,32 @@ int main(int argc, char** argv) {
std::cout << "num_trials=" << num_trials << std::endl;
std::cout << "method=" << method << std::endl;

#ifdef BUILD_WITH_TBB
tbb::global_control tbb_control(tbb::global_control::max_allowed_parallelism, num_threads);
#endif

KittiDataset kitti(dataset_path, 1);
auto raw_points = std::make_shared<PointCloud>(kitti.points[0]);
std::cout << "num_raw_points=" << raw_points->size() << std::endl;

const auto search_voxel_resolution = [&](size_t target_num_points) {
std::pair<double, size_t> left = {0.1, voxelgrid_sampling_tbb(*raw_points, 0.1)->size()};
std::pair<double, size_t> right = {1.0, voxelgrid_sampling_tbb(*raw_points, 1.0)->size()};
std::pair<double, size_t> left = {0.1, voxelgrid_sampling(*raw_points, 0.1)->size()};
std::pair<double, size_t> right = {1.0, voxelgrid_sampling(*raw_points, 1.0)->size()};

for (int i = 0; i < 20; i++) {
if (left.second < target_num_points) {
left.first *= 0.1;
left.second = voxelgrid_sampling_tbb(*raw_points, left.first)->size();
left.second = voxelgrid_sampling(*raw_points, left.first)->size();
continue;
}
if (right.second > target_num_points) {
right.first *= 10.0;
right.second = voxelgrid_sampling_tbb(*raw_points, right.first)->size();
right.second = voxelgrid_sampling(*raw_points, right.first)->size();
continue;
}

const double mid = (left.first + right.first) * 0.5;
const size_t mid_num_points = voxelgrid_sampling_tbb(*raw_points, mid)->size();
const size_t mid_num_points = voxelgrid_sampling(*raw_points, mid)->size();

if (std::abs(1.0 - static_cast<double>(mid_num_points) / target_num_points) < 0.001) {
return mid;
Expand All @@ -89,7 +93,7 @@ int main(int argc, char** argv) {
for (double target = 1.0; target > 0.05; target -= 0.1) {
const double downsampling_resolution = search_voxel_resolution(raw_points->size() * target);
downsampling_resolutions.emplace_back(downsampling_resolution);
downsampled.emplace_back(voxelgrid_sampling_tbb(*raw_points, downsampling_resolution));
downsampled.emplace_back(voxelgrid_sampling(*raw_points, downsampling_resolution));
std::cout << "downsampling_resolution=" << downsampling_resolution << std::endl;
std::cout << "num_points=" << downsampled.back()->size() << std::endl;
}
Expand All @@ -103,11 +107,14 @@ int main(int argc, char** argv) {

if (method == "small") {
UnsafeKdTree<PointCloud> tree(*downsampled);
} else if (method == "tbb") {
UnsafeKdTreeTBB<PointCloud> tree(*downsampled);
} else if (method == "omp") {
UnsafeKdTreeOMP<PointCloud> tree(*downsampled, num_threads);
}
#ifdef BUILD_WITH_TBB
else if (method == "tbb") {
UnsafeKdTreeTBB<PointCloud> tree(*downsampled);
}
#endif
}

Stopwatch sw;
Expand All @@ -127,31 +134,34 @@ int main(int argc, char** argv) {
}
std::cout << "kdtree_times=" << kdtree_times.str() << " [msec]" << std::endl;
}
} else if (method == "tbb") {
} else if (method == "omp") {
for (size_t i = 0; i < downsampling_resolutions.size(); i++) {
Summarizer kdtree_tbb_times(true);
Summarizer kdtree_omp_times(true);
sw.start();
for (size_t j = 0; j < num_trials; j++) {
UnsafeKdTreeTBB<PointCloud> tree(*downsampled[i]);
UnsafeKdTreeOMP<PointCloud> tree(*downsampled[i], num_threads);
sw.lap();
kdtree_tbb_times.push(sw.msec());
kdtree_omp_times.push(sw.msec());
}

std::cout << "kdtree_tbb_times=" << kdtree_tbb_times.str() << " [msec]" << std::endl;
std::cout << "kdtree_omp_times=" << kdtree_omp_times.str() << " [msec]" << std::endl;
}
} else if (method == "omp") {
}
#ifdef BUILD_WITH_TBB
else if (method == "tbb") {
for (size_t i = 0; i < downsampling_resolutions.size(); i++) {
Summarizer kdtree_omp_times(true);
Summarizer kdtree_tbb_times(true);
sw.start();
for (size_t j = 0; j < num_trials; j++) {
UnsafeKdTreeOMP<PointCloud> tree(*downsampled[i], num_threads);
UnsafeKdTreeTBB<PointCloud> tree(*downsampled[i]);
sw.lap();
kdtree_omp_times.push(sw.msec());
kdtree_tbb_times.push(sw.msec());
}

std::cout << "kdtree_omp_times=" << kdtree_omp_times.str() << " [msec]" << std::endl;
std::cout << "kdtree_tbb_times=" << kdtree_tbb_times.str() << " [msec]" << std::endl;
}
}
#endif

return 0;
}

0 comments on commit 75a1ad3

Please sign in to comment.