mirror of https://github.com/koide3/small_gicp.git
go back to C++17
This commit is contained in:
parent
0e6ad9a157
commit
2f11442c60
|
|
@ -1,7 +1,7 @@
|
|||
cmake_minimum_required(VERSION 3.5.2)
|
||||
cmake_minimum_required(VERSION 3.16)
|
||||
project(small_gicp)
|
||||
|
||||
set(CMAKE_CXX_STANDARD 20)
|
||||
set(CMAKE_CXX_STANDARD 17)
|
||||
set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_CURRENT_LIST_DIR}/cmake")
|
||||
|
||||
if(NOT CMAKE_BUILD_TYPE AND NOT CMAKE_CONFIGURATION_TYPES)
|
||||
|
|
|
|||
|
|
@ -14,12 +14,12 @@ Note that GPU-based implementations are NOT included in this package.
|
|||
|
||||
## Requirements
|
||||
|
||||
This library uses some C++20 features. While porting it to older environments should be easy, we have no plan to support environments older than Ubuntu 22.04.
|
||||
This library uses some C++17 features. While porting it to older environments should be easy, we have no plan to support environments older than Ubuntu 20.04.
|
||||
|
||||
## Dependencies
|
||||
|
||||
- [Mandatory] [Eigen](https://eigen.tuxfamily.org/), [nanoflann](https://github.com/jlblancoc/nanoflann) ([bundled1](include/ann/nanoflann.hpp), [bundled2](include/ann/nanoflann_omp.hpp), [bundled3](include/ann/nanoflann_tbb.hpp)), [Sophus](https://github.com/strasdat/Sophus) ([bundled](include/util/lie.hpp))
|
||||
- [Optional] [OpenMP](https://www.openmp.org/), [Intel TBB](https://www.intel.com/content/www/us/en/developer/tools/oneapi/onetbb.html), [PCL](https://pointclouds.org/)
|
||||
- [Mandatory] [Eigen](https://eigen.tuxfamily.org/), [nanoflann](https://github.com/jlblancoc/nanoflann) ([bundled1](include/small_gicp/ann/nanoflann.hpp), [bundled2](include/small_gicp/ann/nanoflann_omp.hpp), [bundled3](include/small_gicp/ann/nanoflann_tbb.hpp)), [Sophus](https://github.com/strasdat/Sophus) ([bundled](include/small_gicp/util/lie.hpp))
|
||||
- [Optional] [OpenMP](https://www.openmp.org/), [Intel TBB](https://www.intel.com/content/www/us/en/developer/tools/oneapi/onetbb.html), [PCL](https://pointclouds.org/), [Iridescence](https://github.com/koide3/iridescence)
|
||||
|
||||
## Installation
|
||||
|
||||
|
|
@ -342,7 +342,7 @@ open3d.visualization.draw_geometries([target_o3d, source_o3d])
|
|||
- Single-threaded `small_gicp::voxelgrid_sampling` is about **1.3x faster** than `pcl::VoxelGrid`.
|
||||
- Multi-threaded `small_gicp::voxelgrid_sampling_tbb` (6 threads) is about **3.2x faster** than `pcl::VoxelGrid`.
|
||||
- `small_gicp::voxelgrid_sampling` gives accurate downsampling results (almost identical to those of `pcl::VoxelGrid`) while `pcl::ApproximateVoxelGrid` yields spurious points (up to 2x points).
|
||||
- `small_gicp::voxelgrid_sampling` can process a larger point cloud with a fine voxel resolution compared to `pcl::VoxelGrid` (for a point cloud of 1000m width, minimum voxel resolution can be 0.5 mm).
|
||||
- `small_gicp::voxelgrid_sampling` can process a larger point cloud with a fine voxel resolution compared to `pcl::VoxelGrid` (for a point cloud of 1000m width, the minimum voxel resolution can be **0.5 mm**).
|
||||
|
||||

|
||||
|
||||
|
|
|
|||
|
|
@ -28,8 +28,8 @@ public:
|
|||
|
||||
CacheTable::const_accessor ca;
|
||||
if (cache.find(ca, coord)) {
|
||||
std::ranges::copy(ca->second.first, k_indices);
|
||||
std::ranges::copy(ca->second.second, k_sq_dists);
|
||||
std::copy(ca->second.first.begin(), ca->first.end(), k_indices);
|
||||
std::copy(ca->second.second.begin(), ca->second.end(), k_sq_dists);
|
||||
return ca->second.first.size();
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -78,14 +78,14 @@ public:
|
|||
/// @brief Get voxel means
|
||||
std::vector<Eigen::Vector4d> voxel_means() const {
|
||||
std::vector<Eigen::Vector4d> means(flat_voxels.size());
|
||||
std::ranges::transform(flat_voxels, means.begin(), [](const GaussianVoxel& voxel) { return voxel.mean; });
|
||||
std::transform(flat_voxels.begin(), flat_voxels.end(), means.begin(), [](const GaussianVoxel& voxel) { return voxel.mean; });
|
||||
return means;
|
||||
}
|
||||
|
||||
/// @brief Get voxel covariances
|
||||
std::vector<Eigen::Matrix4d> voxel_covs() const {
|
||||
std::vector<Eigen::Matrix4d> covs(flat_voxels.size());
|
||||
std::ranges::transform(flat_voxels, covs.begin(), [](const GaussianVoxel& voxel) { return voxel.cov; });
|
||||
std::transform(flat_voxels.begin(), flat_voxels.end(), covs.begin(), [](const GaussianVoxel& voxel) { return voxel.cov; });
|
||||
return covs;
|
||||
}
|
||||
|
||||
|
|
@ -112,7 +112,8 @@ public:
|
|||
|
||||
if ((++lru_counter) % lru_clear_cycle == 0) {
|
||||
// Remove least recently used voxels
|
||||
std::erase_if(flat_voxels, [&](const GaussianVoxel& voxel) { return voxel.lru + lru_horizon < lru_counter; });
|
||||
auto remove_counter = std::remove_if(flat_voxels.begin(), flat_voxels.end(), [&](const GaussianVoxel& voxel) { return voxel.lru + lru_horizon < lru_counter; });
|
||||
flat_voxels.erase(remove_counter, flat_voxels.end());
|
||||
voxels.clear();
|
||||
|
||||
// Rehash
|
||||
|
|
|
|||
|
|
@ -2,6 +2,7 @@
|
|||
// SPDX-License-Identifier: MIT
|
||||
#pragma once
|
||||
|
||||
#include <type_traits>
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace small_gicp {
|
||||
|
|
@ -24,7 +25,13 @@ size_t knn_search(const T& tree, const Eigen::Vector4d& point, size_t k, size_t*
|
|||
}
|
||||
|
||||
template <typename T>
|
||||
concept HasNearestNeighborSearch = requires(const T& tree) { Traits<T>::nearest_neighbor_search(tree, Eigen::Vector4d(), nullptr, nullptr); };
|
||||
struct has_nearest_neighbor_search {
|
||||
template <typename U, int = (&Traits<U>::nearest_neighbor_search, 0)>
|
||||
static std::true_type test(U*);
|
||||
static std::false_type test(...);
|
||||
|
||||
static constexpr bool value = decltype(test((T*)nullptr))::value;
|
||||
};
|
||||
|
||||
/// @brief Find the nearest neighbor
|
||||
/// @param tree Nearest neighbor search (e.g., KdTree)
|
||||
|
|
@ -32,12 +39,12 @@ concept HasNearestNeighborSearch = requires(const T& tree) { Traits<T>::nearest_
|
|||
/// @param k_index [out] Index of the nearest neighbor
|
||||
/// @param k_sq_dist [out] Squared distance to the nearest neighbor
|
||||
/// @return 1 if a neighbor is found else 0
|
||||
template <HasNearestNeighborSearch T>
|
||||
template <typename T, std::enable_if_t<has_nearest_neighbor_search<T>::value, bool> = true>
|
||||
size_t nearest_neighbor_search(const T& tree, const Eigen::Vector4d& point, size_t* k_index, double* k_sq_dist) {
|
||||
return Traits<T>::nearest_neighbor_search(tree, point, k_index, k_sq_dist);
|
||||
}
|
||||
|
||||
template <typename T>
|
||||
template <typename T, std::enable_if_t<!has_nearest_neighbor_search<T>::value, bool> = true>
|
||||
size_t nearest_neighbor_search(const T& tree, const Eigen::Vector4d& point, size_t* k_index, double* k_sq_dist) {
|
||||
return Traits<T>::knn_search(tree, point, 1, k_index, k_sq_dist);
|
||||
}
|
||||
|
|
|
|||
|
|
@ -57,7 +57,7 @@ public:
|
|||
}
|
||||
|
||||
std::vector<double> sorted(full_data.begin(), full_data.end());
|
||||
std::ranges::nth_element(sorted, sorted.begin() + sorted.size() / 2);
|
||||
std::nth_element(sorted.begin(), sorted.end(), sorted.begin() + sorted.size() / 2);
|
||||
return sorted[sorted.size() / 2];
|
||||
}
|
||||
|
||||
|
|
@ -105,19 +105,19 @@ public:
|
|||
filenames.emplace_back(path.path().string());
|
||||
}
|
||||
|
||||
std::ranges::sort(filenames);
|
||||
std::sort(filenames.begin(), filenames.end());
|
||||
if (filenames.size() > max_num_data) {
|
||||
filenames.resize(max_num_data);
|
||||
}
|
||||
|
||||
points.resize(filenames.size());
|
||||
std::ranges::transform(filenames, points.begin(), [](const std::string& filename) { return read_points(filename); });
|
||||
std::transform(filenames.begin(), filenames.end(), points.begin(), [](const std::string& filename) { return read_points(filename); });
|
||||
}
|
||||
|
||||
template <typename PointCloud>
|
||||
std::vector<std::shared_ptr<PointCloud>> convert(bool release = false) {
|
||||
std::vector<std::shared_ptr<PointCloud>> converted(points.size());
|
||||
std::ranges::transform(points, converted.begin(), [=](auto& raw_points) {
|
||||
std::transform(points.begin(), points.end(), converted.begin(), [=](auto& raw_points) {
|
||||
auto points = std::make_shared<PointCloud>();
|
||||
traits::resize(*points, raw_points.size());
|
||||
for (size_t i = 0; i < raw_points.size(); i++) {
|
||||
|
|
|
|||
|
|
@ -64,7 +64,7 @@ static std::vector<Eigen::Vector4f> read_ply(const std::string& filename) {
|
|||
break;
|
||||
}
|
||||
|
||||
if (line.starts_with("element")) {
|
||||
if (line.find("element") == 0) {
|
||||
std::stringstream sst(line);
|
||||
std::string token, vertex, num_points;
|
||||
sst >> token >> vertex >> num_points;
|
||||
|
|
@ -74,7 +74,7 @@ static std::vector<Eigen::Vector4f> read_ply(const std::string& filename) {
|
|||
}
|
||||
|
||||
points.resize(std::stol(num_points));
|
||||
} else if (line.starts_with("property")) {
|
||||
} else if (line.find("property") == 0) {
|
||||
std::stringstream sst(line);
|
||||
std::string token, type, name;
|
||||
sst >> token >> type >> name;
|
||||
|
|
|
|||
|
|
@ -3,6 +3,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
#include <vector>
|
||||
#include <Eigen/Core>
|
||||
#include <small_gicp/points/traits.hpp>
|
||||
|
||||
|
|
|
|||
|
|
@ -54,7 +54,7 @@ struct GaussNewtonOptimizer {
|
|||
result.error = e;
|
||||
}
|
||||
|
||||
result.num_inliers = std::ranges::count_if(factors, [](const auto& factor) { return factor.inlier(); });
|
||||
result.num_inliers = std::count_if(factors.begin(), factors.end(), [](const auto& factor) { return factor.inlier(); });
|
||||
|
||||
return result;
|
||||
}
|
||||
|
|
@ -128,7 +128,7 @@ struct LevenbergMarquardtOptimizer {
|
|||
result.error = e;
|
||||
}
|
||||
|
||||
result.num_inliers = std::ranges::count_if(factors, [](const auto& factor) { return factor.inlier(); });
|
||||
result.num_inliers = std::count_if(factors.begin(), factors.end(), [](const auto& factor) { return factor.inlier(); });
|
||||
|
||||
return result;
|
||||
}
|
||||
|
|
|
|||
|
|
@ -2,6 +2,7 @@
|
|||
// SPDX-License-Identifier: MIT
|
||||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <Eigen/Core>
|
||||
|
||||
namespace small_gicp {
|
||||
|
|
|
|||
|
|
@ -48,7 +48,7 @@ std::shared_ptr<OutputPointCloud> voxelgrid_sampling(const InputPointCloud& poin
|
|||
|
||||
// Sort by voxel coord
|
||||
const auto compare = [](const auto& lhs, const auto& rhs) { return lhs.first < rhs.first; };
|
||||
std::ranges::sort(coord_pt, compare);
|
||||
std::sort(coord_pt.begin(), coord_pt.end(), compare);
|
||||
|
||||
auto downsampled = std::make_shared<OutputPointCloud>();
|
||||
traits::resize(*downsampled, traits::size(points));
|
||||
|
|
|
|||
|
|
@ -13,7 +13,7 @@ size_t register_odometry(const std::string& name, std::function<OdometryEstimati
|
|||
|
||||
std::vector<std::string> odometry_names() {
|
||||
std::vector<std::string> names(odometry_registry.size());
|
||||
std::ranges::transform(odometry_registry.begin(), odometry_registry.end(), names.begin(), [](const auto& p) { return p.first; });
|
||||
std::transform(odometry_registry.begin(), odometry_registry.end(), names.begin(), [](const auto& p) { return p.first; });
|
||||
return names;
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -120,7 +120,7 @@ TEST_F(KdTreeTest, LoadCheck) {
|
|||
for (size_t i = 0; i < queries.size(); i++) {
|
||||
EXPECT_EQ(k_indices[i].size(), k);
|
||||
EXPECT_EQ(k_sq_dists[i].size(), k);
|
||||
EXPECT_TRUE(std::ranges::is_sorted(k_sq_dists[i])) << "Must be sorted by distance";
|
||||
EXPECT_TRUE(std::is_sorted(k_sq_dists[i].begin(), k_sq_dists[i].end())) << "Must be sorted by distance";
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -47,7 +47,7 @@ TEST(PointsTest, PointsTest) {
|
|||
std::uniform_real_distribution<> dist(-100.0, 100.0);
|
||||
|
||||
std::vector<Eigen::Vector4d> src_points(100);
|
||||
std::ranges::generate(src_points, [&] { return Eigen::Vector4d(dist(mt), dist(mt), dist(mt), 1.0); });
|
||||
std::generate(src_points.begin(), src_points.end(), [&] { return Eigen::Vector4d(dist(mt), dist(mt), dist(mt), 1.0); });
|
||||
|
||||
auto points = std::make_shared<PointCloud>(src_points);
|
||||
test_points(src_points, *points, mt);
|
||||
|
|
|
|||
|
|
@ -80,7 +80,7 @@ public:
|
|||
const Eigen::Isometry3d T_shifted_source = T_source_shifted[i].inverse();
|
||||
|
||||
shifted[i] = std::make_shared<PointCloud>(source->points);
|
||||
std::ranges::transform(source->points, shifted[i]->points.begin(), [&](const auto& p) -> Eigen::Vector4d { return T_shifted_source * p; });
|
||||
std::transform(source->points.begin(), source->points.end(), shifted[i]->points.begin(), [&](const auto& p) -> Eigen::Vector4d { return T_shifted_source * p; });
|
||||
estimate_normals_covariances_omp(*shifted[i]);
|
||||
}
|
||||
|
||||
|
|
|
|||
|
|
@ -32,10 +32,10 @@ TEST(SortOMP, MergeSortTest) {
|
|||
for (int i = 0; i < 100; i++) {
|
||||
std::uniform_int_distribution<> data_dist(-100, 100);
|
||||
std::vector<int> data(size_dist(mt));
|
||||
std::ranges::generate(data, [&] { return data_dist(mt); });
|
||||
std::generate(data.begin(), data.end(), [&] { return data_dist(mt); });
|
||||
|
||||
std::vector<int> sorted = data;
|
||||
std::ranges::sort(sorted);
|
||||
std::sort(sorted.begin(), sorted.end());
|
||||
|
||||
std::vector<int> sorted_omp = data;
|
||||
merge_sort_omp(sorted_omp.begin(), sorted_omp.end(), std::less<int>(), 4);
|
||||
|
|
@ -47,10 +47,10 @@ TEST(SortOMP, MergeSortTest) {
|
|||
for (int i = 0; i < 100; i++) {
|
||||
std::uniform_real_distribution<> data_dist(-100, 100);
|
||||
std::vector<double> data(size_dist(mt));
|
||||
std::ranges::generate(data, [&] { return data_dist(mt); });
|
||||
std::generate(data.begin(), data.end(), [&] { return data_dist(mt); });
|
||||
|
||||
std::vector<double> sorted = data;
|
||||
std::ranges::sort(sorted);
|
||||
std::sort(sorted.begin(), sorted.end());
|
||||
|
||||
std::vector<double> sorted_omp = data;
|
||||
merge_sort_omp(sorted_omp.begin(), sorted_omp.end(), std::less<double>(), 4);
|
||||
|
|
@ -74,10 +74,10 @@ TEST(SortOMP, QuickSortTest) {
|
|||
for (int i = 0; i < 100; i++) {
|
||||
std::uniform_int_distribution<> data_dist(-100, 100);
|
||||
std::vector<int> data(size_dist(mt));
|
||||
std::ranges::generate(data, [&] { return data_dist(mt); });
|
||||
std::generate(data.begin(), data.end(), [&] { return data_dist(mt); });
|
||||
|
||||
std::vector<int> sorted = data;
|
||||
std::ranges::sort(sorted);
|
||||
std::sort(sorted.begin(), sorted.end());
|
||||
|
||||
std::vector<int> sorted_omp = data;
|
||||
quick_sort_omp(sorted_omp.begin(), sorted_omp.end(), std::less<int>(), 4);
|
||||
|
|
@ -89,10 +89,10 @@ TEST(SortOMP, QuickSortTest) {
|
|||
for (int i = 0; i < 100; i++) {
|
||||
std::uniform_real_distribution<> data_dist(-100, 100);
|
||||
std::vector<double> data(size_dist(mt));
|
||||
std::ranges::generate(data, [&] { return data_dist(mt); });
|
||||
std::generate(data.begin(), data.end(), [&] { return data_dist(mt); });
|
||||
|
||||
std::vector<double> sorted = data;
|
||||
std::ranges::sort(sorted);
|
||||
std::sort(sorted.begin(), sorted.end());
|
||||
|
||||
std::vector<double> sorted_omp = data;
|
||||
quick_sort_omp(sorted_omp.begin(), sorted_omp.end(), std::less<double>(), 4);
|
||||
|
|
|
|||
Loading…
Reference in New Issue