mirror of https://github.com/koide3/small_gicp.git
Compare commits
14 Commits
| Author | SHA1 | Date |
|---|---|---|
|
|
1d8cce8add | |
|
|
08bc50beff | |
|
|
9befefb198 | |
|
|
3466ea263a | |
|
|
df145cbb15 | |
|
|
db2f8e6646 | |
|
|
2c5e9e6092 | |
|
|
ff63d5ef76 | |
|
|
13e0a75cc1 | |
|
|
8e665814a9 | |
|
|
4e8e745800 | |
|
|
e669301de3 | |
|
|
f127ae7a51 | |
|
|
d6b0cb8e99 |
|
|
@ -13,7 +13,7 @@ on:
|
|||
|
||||
jobs:
|
||||
coverage:
|
||||
runs-on: ubuntu-22.04
|
||||
runs-on: ubuntu-24.04
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
|
|
@ -23,7 +23,7 @@ jobs:
|
|||
- name: Install Dependencies
|
||||
run: |
|
||||
sudo apt-get -y update
|
||||
sudo apt-get install --no-install-recommends -y build-essential cmake python3-pip pybind11-dev libeigen3-dev libfmt-dev libtbb-dev libomp-dev libpcl-dev libgtest-dev lcov
|
||||
sudo apt-get install --no-install-recommends -y build-essential cmake python3-pip pybind11-dev libeigen3-dev libfmt-dev libtbb-dev libomp-dev libpcl-dev libgtest-dev lcov ninja-build
|
||||
pip install -U setuptools pytest pytest-cov numpy scipy
|
||||
|
||||
- name: Build (C++)
|
||||
|
|
|
|||
|
|
@ -13,7 +13,7 @@ on:
|
|||
|
||||
jobs:
|
||||
test:
|
||||
runs-on: ubuntu-22.04
|
||||
runs-on: ubuntu-24.04
|
||||
|
||||
steps:
|
||||
- uses: actions/checkout@v2
|
||||
|
|
@ -23,7 +23,7 @@ jobs:
|
|||
- name: Install Dependencies
|
||||
run: |
|
||||
sudo apt-get -y update
|
||||
sudo apt-get install --no-install-recommends -y build-essential cmake python3-pip pybind11-dev libeigen3-dev libfmt-dev libtbb-dev libomp-dev libpcl-dev libgtest-dev
|
||||
sudo apt-get install --no-install-recommends -y build-essential cmake python3-pip pybind11-dev libeigen3-dev libfmt-dev libtbb-dev libomp-dev libpcl-dev libgtest-dev ninja-build
|
||||
pip install -U setuptools pytest numpy scipy
|
||||
|
||||
- name: Build
|
||||
|
|
|
|||
|
|
@ -129,5 +129,5 @@ small_vgicp : APE=5.956 +- 2.725 RPE(100)=1.315 +- 0.762 RPE(400)=6.8
|
|||
|
||||
[Code](https://github.com/koide3/small_gicp/blob/pybench/src/benchmark/odometry_benchmark.py)
|
||||
|
||||
Processing speed comparison between small_gicp and Open3D ([youtube]((https://youtu.be/LNESzGXPr4c?feature=shared))).
|
||||
Processing speed comparison between small_gicp and Open3D ([youtube](https://youtu.be/LNESzGXPr4c?feature=shared)).
|
||||
[](https://youtu.be/LNESzGXPr4c?feature=shared)
|
||||
|
|
|
|||
|
|
@ -0,0 +1,32 @@
|
|||
cff-version: "1.2.0"
|
||||
authors:
|
||||
- family-names: Koide
|
||||
given-names: Kenji
|
||||
orcid: "https://orcid.org/0000-0001-5361-1428"
|
||||
contact:
|
||||
- family-names: Koide
|
||||
given-names: Kenji
|
||||
orcid: "https://orcid.org/0000-0001-5361-1428"
|
||||
doi: 10.5281/zenodo.13283012
|
||||
message: If you use this software, please cite our article in the
|
||||
Journal of Open Source Software.
|
||||
preferred-citation:
|
||||
authors:
|
||||
- family-names: Koide
|
||||
given-names: Kenji
|
||||
orcid: "https://orcid.org/0000-0001-5361-1428"
|
||||
date-published: 2024-08-10
|
||||
doi: 10.21105/joss.06948
|
||||
issn: 2475-9066
|
||||
issue: 100
|
||||
journal: Journal of Open Source Software
|
||||
publisher:
|
||||
name: Open Journals
|
||||
start: 6948
|
||||
title: "small_gicp: Efficient and parallel algorithms for point cloud
|
||||
registration"
|
||||
type: article
|
||||
url: "https://joss.theoj.org/papers/10.21105/joss.06948"
|
||||
volume: 9
|
||||
title: "small_gicp: Efficient and parallel algorithms for point cloud
|
||||
registration"
|
||||
|
|
@ -97,7 +97,10 @@ endif()
|
|||
|
||||
if(MSVC)
|
||||
add_compile_definitions(_USE_MATH_DEFINES)
|
||||
# add_compile_options(/openmp:llvm)
|
||||
add_compile_options(/bigobj)
|
||||
if(BUILD_WITH_OPENMP)
|
||||
add_compile_options(/openmp:llvm)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
##############
|
||||
|
|
@ -111,8 +114,8 @@ if(ENABLE_COVERAGE)
|
|||
find_program(GENHTML genhtml REQUIRED)
|
||||
|
||||
add_custom_target(coverage
|
||||
COMMAND ${LCOV} --directory . --capture --output-file coverage.info
|
||||
COMMAND ${LCOV} --remove coverage.info -o coverage.info '/usr/*'
|
||||
COMMAND ${LCOV} --directory . --capture --output-file coverage.info --ignore-errors mismatch
|
||||
COMMAND ${LCOV} --remove coverage.info -o coverage.info '/usr/*' --ignore-errors mismatch
|
||||
COMMAND ${GENHTML} --demangle-cpp -o coverage coverage.info
|
||||
WORKING_DIRECTORY ${CMAKE_BINARY_DIR})
|
||||
endif()
|
||||
|
|
@ -247,6 +250,12 @@ if(BUILD_EXAMPLES)
|
|||
TBB::tbbmalloc
|
||||
PCL::PCL
|
||||
)
|
||||
if(MSVC)
|
||||
set_target_properties(${EXAMPLE_NAME}
|
||||
PROPERTIES VS_DEBUGGER_WORKING_DIRECTORY
|
||||
"${CMAKE_SOURCE_DIR}"
|
||||
)
|
||||
endif()
|
||||
endforeach()
|
||||
endif()
|
||||
|
||||
|
|
@ -273,6 +282,13 @@ if(BUILD_TESTS)
|
|||
)
|
||||
|
||||
gtest_discover_tests(${TEST_NAME} WORKING_DIRECTORY ${CMAKE_SOURCE_DIR})
|
||||
|
||||
if(MSVC)
|
||||
set_target_properties(${TEST_NAME}
|
||||
PROPERTIES VS_DEBUGGER_WORKING_DIRECTORY
|
||||
"${CMAKE_SOURCE_DIR}"
|
||||
)
|
||||
endif()
|
||||
endforeach()
|
||||
endif()
|
||||
|
||||
|
|
|
|||
22
README.md
22
README.md
|
|
@ -10,10 +10,10 @@
|
|||
|
||||
Note that GPU-based implementations are NOT included in this package.
|
||||
|
||||
If you find this package useful for your project, please consider leaving a comment [here](https://github.com/koide3/small_gicp/issues/3). It would help the author receive recognition in his organization and keep working on this project.
|
||||
If you find this package useful for your project, please consider leaving a comment [here](https://github.com/koide3/small_gicp/issues/3). It would help the author receive recognition in his organization and keep working on this project. Please also cite [the corresponding software paper](https://joss.theoj.org/papers/10.21105/joss.06948) if you use this software in an academic work.
|
||||
|
||||
|
||||
[](https://github.com/koide3/small_gicp/actions/workflows/build-linux.yml) [](https://github.com/koide3/small_gicp/actions/workflows/build-macos.yml) [](https://github.com/koide3/small_gicp/actions/workflows/build-windows.yml) [](https://github.com/koide3/small_gicp/actions/workflows/test.yml) [](https://codecov.io/gh/koide3/small_gicp)
|
||||
[](https://joss.theoj.org/papers/059b017c823ed9fd211fc91373cdc2cc) [](https://github.com/koide3/small_gicp/actions/workflows/build-linux.yml) [](https://github.com/koide3/small_gicp/actions/workflows/build-macos.yml) [](https://github.com/koide3/small_gicp/actions/workflows/build-windows.yml) [](https://github.com/koide3/small_gicp/actions/workflows/test.yml) [](https://codecov.io/gh/koide3/small_gicp)
|
||||
|
||||
## Requirements
|
||||
|
||||
|
|
@ -431,7 +431,7 @@ python3 src/example/basic_registration.py
|
|||
|
||||
## [Benchmark](BENCHMARK.md)
|
||||
|
||||
Processing speed comparison between small_gicp and Open3D ([youtube]((https://youtu.be/LNESzGXPr4c?feature=shared))).
|
||||
Processing speed comparison between small_gicp and Open3D ([youtube](https://youtu.be/LNESzGXPr4c?feature=shared)).
|
||||
[](https://youtu.be/LNESzGXPr4c?feature=shared)
|
||||
|
||||
### Downsampling
|
||||
|
|
@ -465,6 +465,22 @@ This package is released under the MIT license.
|
|||
|
||||
If you find this package useful for your project, please consider leaving a comment [here](https://github.com/koide3/small_gicp/issues/3). It would help the author receive recognition in his organization and keep working on this project.
|
||||
|
||||
Please also cite [the following article](https://joss.theoj.org/papers/10.21105/joss.06948) if you use this software in an academic work.
|
||||
|
||||
```
|
||||
@article{small_gicp,
|
||||
author = {Kenji Koide},
|
||||
title = {{small\_gicp: Efficient and parallel algorithms for point cloud registration}},
|
||||
journal = {Journal of Open Source Software},
|
||||
month = aug,
|
||||
number = {100},
|
||||
pages = {6948},
|
||||
volume = {9},
|
||||
year = {2024},
|
||||
doi = {10.21105/joss.06948}
|
||||
}
|
||||
```
|
||||
|
||||
## Contact
|
||||
|
||||
[Kenji Koide](https://staff.aist.go.jp/k.koide/), National Institute of Advanced Industrial Science and Technology (AIST)
|
||||
|
|
|
|||
|
|
@ -7,7 +7,7 @@ ENV DEBIAN_FRONTEND=noninteractive
|
|||
RUN apt-get update && apt-get install --no-install-recommends -y \
|
||||
&& apt-get install --no-install-recommends -y \
|
||||
wget nano build-essential git cmake python3-dev python3-pip pybind11-dev \
|
||||
libeigen3-dev libomp-dev
|
||||
libeigen3-dev libomp-dev ninja-build
|
||||
|
||||
RUN mkdir -p ~/.config/pip
|
||||
RUN echo "[global]\nbreak-system-packages=true" > ~/.config/pip/pip.conf
|
||||
|
|
|
|||
|
|
@ -7,7 +7,7 @@ ENV DEBIAN_FRONTEND=noninteractive
|
|||
RUN apt-get update && apt-get install --no-install-recommends -y \
|
||||
&& apt-get install --no-install-recommends -y \
|
||||
wget nano build-essential git cmake python3-dev python3-pip pybind11-dev \
|
||||
libeigen3-dev libomp-dev
|
||||
libeigen3-dev libomp-dev ninja-build
|
||||
|
||||
RUN apt-get update && apt-get install --no-install-recommends -y \
|
||||
&& apt-get install --no-install-recommends -y \
|
||||
|
|
|
|||
|
|
@ -34,6 +34,7 @@ public:
|
|||
/// This class supports incremental point cloud insertion and LRU-based voxel deletion that removes voxels that are not recently referenced.
|
||||
/// @note This class can be used as a point cloud as well as a neighbor search structure.
|
||||
/// @note This class can handle arbitrary number of voxels and arbitrary range of voxel coordinates (in 32-bit int range).
|
||||
/// @note To use this as a source point cloud for registration, use `SequentialVoxelMapAccessor`.
|
||||
template <typename VoxelContents>
|
||||
struct IncrementalVoxelMap {
|
||||
public:
|
||||
|
|
|
|||
|
|
@ -0,0 +1,219 @@
|
|||
// SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
|
||||
// SPDX-License-Identifier: MIT
|
||||
#pragma once
|
||||
|
||||
#include <cmath>
|
||||
#include <Eigen/Core>
|
||||
#include <small_gicp/points/traits.hpp>
|
||||
#include <small_gicp/ann/knn_result.hpp>
|
||||
|
||||
namespace small_gicp {
|
||||
|
||||
/// @brief Equirectangular projection.
|
||||
struct EquirectangularProjection {
|
||||
public:
|
||||
/// @brief Project the point into the normalized image coordinates. (u, v) in ([0, 1], [0, 1])
|
||||
Eigen::Vector2d operator()(const Eigen::Vector3d& pt_3d) const {
|
||||
if (pt_3d.squaredNorm() < 1e-3) {
|
||||
return Eigen::Vector2d(0.5, 0.5);
|
||||
}
|
||||
|
||||
const Eigen::Vector3d bearing = pt_3d.normalized();
|
||||
const double lat = -std::asin(bearing[1]);
|
||||
const double lon = std::atan2(bearing[0], bearing[2]);
|
||||
|
||||
return Eigen::Vector2d(lon / (2.0 * M_PI) + 0.5, lat / M_PI + 0.5);
|
||||
};
|
||||
};
|
||||
|
||||
/// @brief Border clamp mode. Points out of the border are discarded.
|
||||
struct BorderClamp {
|
||||
public:
|
||||
int operator()(int x, int width) const { return x; }
|
||||
};
|
||||
|
||||
/// @brief Border repeat mode. Points out of the border are wrapped around.
|
||||
struct BorderRepeat {
|
||||
public:
|
||||
int operator()(int x, int width) const { return x < 0 ? x + width : (x >= width ? x - width : x); }
|
||||
};
|
||||
|
||||
/// @brief "Unsafe" projective search. This class does not hold the ownership of the target point cloud.
|
||||
template <typename PointCloud, typename Projection = EquirectangularProjection, typename BorderModeH = BorderRepeat, typename BorderModeV = BorderClamp>
|
||||
struct UnsafeProjectiveSearch {
|
||||
public:
|
||||
/// @brief Constructor.
|
||||
/// @param width Index map width
|
||||
/// @param height Index map height
|
||||
/// @param points Target point cloud
|
||||
UnsafeProjectiveSearch(int width, int height, const PointCloud& points) : points(points), index_map(height, width), search_window_h(10), search_window_v(5) {
|
||||
index_map.setConstant(invalid_index);
|
||||
|
||||
Projection project;
|
||||
for (size_t i = 0; i < traits::size(points); ++i) {
|
||||
const Eigen::Vector4d pt = traits::point(points, i);
|
||||
const Eigen::Vector2d uv = project(pt.head<3>());
|
||||
const int u = uv[0] * index_map.cols();
|
||||
const int v = uv[1] * index_map.rows();
|
||||
|
||||
if (u < 0 || u >= index_map.cols() || v < 0 || v >= index_map.rows()) {
|
||||
continue;
|
||||
}
|
||||
index_map(v, u) = i;
|
||||
}
|
||||
}
|
||||
|
||||
/// @brief Find the nearest neighbor.
|
||||
/// @param query Query point
|
||||
/// @param k_indices Index of the nearest neighbor (uninitialized if not found)
|
||||
/// @param k_sq_dists Squared distance to the nearest neighbor (uninitialized if not found)
|
||||
/// @param setting KNN search setting
|
||||
/// @return Number of found neighbors (0 or 1)
|
||||
size_t nearest_neighbor_search(const Eigen::Vector4d& query, size_t* k_indices, double* k_sq_dists, const KnnSetting& setting = KnnSetting()) const {
|
||||
return knn_search<1>(query, k_indices, k_sq_dists, setting);
|
||||
}
|
||||
|
||||
/// @brief Find k-nearest neighbors. This method uses dynamic memory allocation.
|
||||
/// @param query Query point
|
||||
/// @param k Number of neighbors
|
||||
/// @param k_indices Indices of neighbors
|
||||
/// @param k_sq_dists Squared distances to neighbors (sorted in ascending order)
|
||||
/// @param setting KNN search setting
|
||||
/// @return Number of found neighbors
|
||||
size_t knn_search(const Eigen::Vector4d& query, int k, size_t* k_indices, double* k_sq_dists, const KnnSetting& setting = KnnSetting()) const {
|
||||
KnnResult<-1> result(k_indices, k_sq_dists, k);
|
||||
knn_search(query, result, setting);
|
||||
return result.num_found();
|
||||
}
|
||||
|
||||
/// @brief Find k-nearest neighbors. This method uses fixed and static memory allocation. Might be faster for small k.
|
||||
/// @param query Query point
|
||||
/// @param k_indices Indices of neighbors
|
||||
/// @param k_sq_dists Squared distances to neighbors (sorted in ascending order)
|
||||
/// @param setting KNN search setting
|
||||
/// @return Number of found neighbors
|
||||
template <int N>
|
||||
size_t knn_search(const Eigen::Vector4d& query, size_t* k_indices, double* k_sq_dists, const KnnSetting& setting = KnnSetting()) const {
|
||||
KnnResult<N> result(k_indices, k_sq_dists);
|
||||
knn_search(query, result, setting);
|
||||
return result.num_found();
|
||||
}
|
||||
|
||||
private:
|
||||
template <typename Result>
|
||||
void knn_search(const Eigen::Vector4d& query, Result& result, const KnnSetting& setting) const {
|
||||
BorderModeH border_h;
|
||||
BorderModeV border_v;
|
||||
|
||||
Projection project;
|
||||
const Eigen::Vector2d uv = project(query.head<3>());
|
||||
const int u = uv[0] * index_map.cols();
|
||||
const int v = uv[1] * index_map.rows();
|
||||
|
||||
for (int du = -search_window_h; du <= search_window_h; du++) {
|
||||
const int u_clamped = border_h(u + du, index_map.cols());
|
||||
if (u_clamped < 0 || u_clamped >= index_map.cols()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
for (int dv = -search_window_v; dv <= search_window_v; dv++) {
|
||||
const int v_clamped = border_v(v + dv, index_map.rows());
|
||||
if (v_clamped < 0 || v_clamped >= index_map.rows()) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const auto index = index_map(v_clamped, u_clamped);
|
||||
if (index == invalid_index) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const double sq_dist = (traits::point(points, index) - query).squaredNorm();
|
||||
result.push(index, sq_dist);
|
||||
|
||||
if (setting.fulfilled(result)) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public:
|
||||
static constexpr std::uint32_t invalid_index = std::numeric_limits<std::uint32_t>::max();
|
||||
|
||||
const PointCloud& points;
|
||||
Eigen::Matrix<std::uint32_t, -1, -1> index_map;
|
||||
|
||||
int search_window_h;
|
||||
int search_window_v;
|
||||
};
|
||||
|
||||
/// @brief "Safe" projective search. This class holds the ownership of the target point cloud.
|
||||
template <typename PointCloud, typename Projection = EquirectangularProjection, typename BorderModeH = BorderRepeat, typename BorderModeV = BorderClamp>
|
||||
struct ProjectiveSearch {
|
||||
public:
|
||||
using Ptr = std::shared_ptr<ProjectiveSearch<PointCloud, Projection>>;
|
||||
using ConstPtr = std::shared_ptr<const ProjectiveSearch<PointCloud, Projection>>;
|
||||
|
||||
explicit ProjectiveSearch(int width, int height, std::shared_ptr<const PointCloud> points) : points(points), search(width, height, *points) {}
|
||||
|
||||
/// @brief Find k-nearest neighbors. This method uses dynamic memory allocation.
|
||||
/// @param query Query point
|
||||
/// @param k Number of neighbors
|
||||
/// @param k_indices Indices of neighbors
|
||||
/// @param k_sq_dists Squared distances to neighbors (sorted in ascending order)
|
||||
/// @param setting KNN search setting
|
||||
/// @return Number of found neighbors
|
||||
size_t nearest_neighbor_search(const Eigen::Vector4d& query, size_t* k_indices, double* k_sq_dists, const KnnSetting& setting = KnnSetting()) const {
|
||||
return search.nearest_neighbor_search(query, k_indices, k_sq_dists, setting);
|
||||
}
|
||||
|
||||
/// @brief Find k-nearest neighbors. This method uses dynamic memory allocation.
|
||||
/// @param query Query point
|
||||
/// @param k Number of neighbors
|
||||
/// @param k_indices Indices of neighbors
|
||||
/// @param k_sq_dists Squared distances to neighbors (sorted in ascending order)
|
||||
/// @param setting KNN search setting
|
||||
/// @return Number of found neighbors
|
||||
size_t knn_search(const Eigen::Vector4d& query, size_t k, size_t* k_indices, double* k_sq_dists, const KnnSetting& setting = KnnSetting()) const {
|
||||
return search.knn_search(query, k, k_indices, k_sq_dists, setting);
|
||||
}
|
||||
|
||||
public:
|
||||
const std::shared_ptr<const PointCloud> points; ///< Points
|
||||
const UnsafeProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV> search; ///< Search
|
||||
};
|
||||
|
||||
namespace traits {
|
||||
|
||||
template <typename PointCloud, typename Projection, typename BorderModeH, typename BorderModeV>
|
||||
struct Traits<UnsafeProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV>> {
|
||||
static size_t nearest_neighbor_search(
|
||||
const UnsafeProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV>& tree,
|
||||
const Eigen::Vector4d& point,
|
||||
size_t* k_indices,
|
||||
double* k_sq_dists) {
|
||||
return tree.nearest_neighbor_search(point, k_indices, k_sq_dists);
|
||||
}
|
||||
|
||||
static size_t
|
||||
knn_search(const UnsafeProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV>& tree, const Eigen::Vector4d& point, size_t k, size_t* k_indices, double* k_sq_dists) {
|
||||
return tree.knn_search(point, k, k_indices, k_sq_dists);
|
||||
}
|
||||
};
|
||||
|
||||
template <typename PointCloud, typename Projection, typename BorderModeH, typename BorderModeV>
|
||||
struct Traits<ProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV>> {
|
||||
static size_t
|
||||
nearest_neighbor_search(const ProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV>& tree, const Eigen::Vector4d& point, size_t* k_indices, double* k_sq_dists) {
|
||||
return tree.nearest_neighbor_search(point, k_indices, k_sq_dists);
|
||||
}
|
||||
|
||||
static size_t
|
||||
knn_search(const ProjectiveSearch<PointCloud, Projection, BorderModeH, BorderModeV>& tree, const Eigen::Vector4d& point, size_t k, size_t* k_indices, double* k_sq_dists) {
|
||||
return tree.knn_search(point, k, k_indices, k_sq_dists);
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace traits
|
||||
|
||||
} // namespace small_gicp
|
||||
|
|
@ -0,0 +1,58 @@
|
|||
// SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
|
||||
// SPDX-License-Identifier: MIT
|
||||
#pragma once
|
||||
|
||||
#include <small_gicp/points/traits.hpp>
|
||||
#include <small_gicp/ann/incremental_voxelmap.hpp>
|
||||
|
||||
namespace small_gicp {
|
||||
|
||||
/**
|
||||
* @brief A wrapper class to sequentially access points in a voxelmap (e.g., using points in a voxelmap as source point cloud for registration).
|
||||
* @note If the contents of the voxelmap are changed, the accessor must be recreated.
|
||||
* @example
|
||||
small_gicp::IncrementalVoxelMap<small_gicp::FlatContainerCov>::Ptr last_voxelmap = ...;
|
||||
small_gicp::IncrementalVoxelMap<small_gicp::FlatContainerCov>::Ptr voxelmap = ...;
|
||||
|
||||
// Create a sequential accessor
|
||||
const auto accessor = small_gicp::create_sequential_accessor(*voxelmap);
|
||||
|
||||
// Use the voxelmap as a source point cloud
|
||||
small_gicp::Registration<small_gicp::GICPFactor, small_gicp::ParallelReductionOMP> registration;
|
||||
auto result = registration.align(*last_voxelmap, accessor, *last_voxelmap, Eigen::Isometry3d::Identity());
|
||||
*/
|
||||
template <typename VoxelMap>
|
||||
class SequentialVoxelMapAccessor {
|
||||
public:
|
||||
/// @brief Constructor.
|
||||
/// @param voxelmap Voxelmap
|
||||
SequentialVoxelMapAccessor(const VoxelMap& voxelmap) : voxelmap(voxelmap), indices(traits::point_indices(voxelmap)) {}
|
||||
|
||||
/// @brief Number of points in the voxelmap.
|
||||
size_t size() const { return indices.size(); }
|
||||
|
||||
public:
|
||||
const VoxelMap& voxelmap; ///< Voxelmap
|
||||
const std::vector<size_t> indices; ///< Indices of points in the voxelmap
|
||||
};
|
||||
|
||||
/// @brief Create a sequential voxelmap accessor.
|
||||
template <typename VoxelMap>
|
||||
SequentialVoxelMapAccessor<VoxelMap> create_sequential_accessor(const VoxelMap& voxelmap) {
|
||||
return SequentialVoxelMapAccessor<VoxelMap>(voxelmap);
|
||||
}
|
||||
|
||||
template <typename VoxelMap>
|
||||
struct traits::Traits<SequentialVoxelMapAccessor<VoxelMap>> {
|
||||
static size_t size(const SequentialVoxelMapAccessor<VoxelMap>& accessor) { return accessor.size(); }
|
||||
|
||||
static bool has_points(const SequentialVoxelMapAccessor<VoxelMap>& accessor) { return traits::has_points(accessor.voxelmap); }
|
||||
static bool has_normals(const SequentialVoxelMapAccessor<VoxelMap>& accessor) { return traits::has_normals(accessor.voxelmap); }
|
||||
static bool has_covs(const SequentialVoxelMapAccessor<VoxelMap>& accessor) { return traits::has_covs(accessor.voxelmap); }
|
||||
|
||||
static Eigen::Vector4d point(const SequentialVoxelMapAccessor<VoxelMap>& accessor, size_t i) { return traits::point(accessor.voxelmap, accessor.indices[i]); }
|
||||
static Eigen::Vector4d normal(const SequentialVoxelMapAccessor<VoxelMap>& accessor, size_t i) { return traits::normal(accessor.voxelmap, accessor.indices[i]); }
|
||||
static Eigen::Matrix4d cov(const SequentialVoxelMapAccessor<VoxelMap>& accessor, size_t i) { return traits::cov(accessor.voxelmap, accessor.indices[i]); }
|
||||
};
|
||||
|
||||
} // namespace small_gicp
|
||||
|
|
@ -99,8 +99,8 @@ protected:
|
|||
std::string registration_type_; ///< Registration type ("GICP" or "VGICP").
|
||||
bool verbose_; ///< Verbosity flag.
|
||||
|
||||
std::shared_ptr<KdTree<pcl::PointCloud<PointSource>>> target_tree_; ///< KdTree for target point cloud.
|
||||
std::shared_ptr<KdTree<pcl::PointCloud<PointSource>>> source_tree_; ///< KdTree for source point cloud.
|
||||
std::shared_ptr<small_gicp::KdTree<pcl::PointCloud<PointSource>>> target_tree_; ///< KdTree for target point cloud.
|
||||
std::shared_ptr<small_gicp::KdTree<pcl::PointCloud<PointSource>>> source_tree_; ///< KdTree for source point cloud.
|
||||
|
||||
std::shared_ptr<GaussianVoxelMap> target_voxelmap_; ///< VoxelMap for target point cloud.
|
||||
std::shared_ptr<GaussianVoxelMap> source_voxelmap_; ///< VoxelMap for source point cloud.
|
||||
|
|
|
|||
|
|
@ -44,7 +44,7 @@ void RegistrationPCL<PointSource, PointTarget>::setInputSource(const PointCloudS
|
|||
}
|
||||
|
||||
pcl::Registration<PointSource, PointTarget, Scalar>::setInputSource(cloud);
|
||||
source_tree_ = std::make_shared<KdTree<pcl::PointCloud<PointSource>>>(input_, KdTreeBuilderOMP(num_threads_));
|
||||
source_tree_ = std::make_shared<small_gicp::KdTree<pcl::PointCloud<PointSource>>>(input_, KdTreeBuilderOMP(num_threads_));
|
||||
source_covs_.clear();
|
||||
source_voxelmap_.reset();
|
||||
}
|
||||
|
|
@ -56,7 +56,7 @@ void RegistrationPCL<PointSource, PointTarget>::setInputTarget(const PointCloudT
|
|||
}
|
||||
|
||||
pcl::Registration<PointSource, PointTarget, Scalar>::setInputTarget(cloud);
|
||||
target_tree_ = std::make_shared<KdTree<pcl::PointCloud<PointTarget>>>(target_, KdTreeBuilderOMP(num_threads_));
|
||||
target_tree_ = std::make_shared<small_gicp::KdTree<pcl::PointCloud<PointTarget>>>(target_, KdTreeBuilderOMP(num_threads_));
|
||||
target_covs_.clear();
|
||||
target_voxelmap_.reset();
|
||||
}
|
||||
|
|
@ -214,7 +214,7 @@ void RegistrationPCL<PointSource, PointTarget>::computeTransformation(PointCloud
|
|||
estimate_covariances_omp(target_proxy, *target_tree_, k_correspondences_, num_threads_);
|
||||
}
|
||||
|
||||
Registration<GICPFactor, ParallelReductionOMP> registration;
|
||||
small_gicp::Registration<GICPFactor, ParallelReductionOMP> registration;
|
||||
registration.criteria.rotation_eps = rotation_epsilon_;
|
||||
registration.criteria.translation_eps = transformation_epsilon_;
|
||||
registration.reduction.num_threads = num_threads_;
|
||||
|
|
|
|||
|
|
@ -2,6 +2,7 @@
|
|||
// SPDX-License-Identifier: MIT
|
||||
#pragma once
|
||||
|
||||
#include <vector>
|
||||
#include <Eigen/Core>
|
||||
#include <small_gicp/points/traits.hpp>
|
||||
|
||||
|
|
@ -15,5 +16,30 @@ struct Traits<Eigen::MatrixXd> {
|
|||
static Eigen::Vector4d point(const Eigen::MatrixXd& points, size_t i) { return Eigen::Vector4d(points(i, 0), points(i, 1), points(i, 2), 1.0); }
|
||||
};
|
||||
|
||||
template <typename Scalar, int D>
|
||||
struct Traits<std::vector<Eigen::Matrix<Scalar, D, 1>>> {
|
||||
static_assert(D == 3 || D == 4, "Only 3D and 4D (homogeneous) points are supported");
|
||||
static_assert(std::is_floating_point<Scalar>::value, "Only floating point types are supported");
|
||||
|
||||
using Point = Eigen::Matrix<Scalar, D, 1>;
|
||||
static size_t size(const std::vector<Point>& points) { return points.size(); }
|
||||
static bool has_points(const std::vector<Point>& points) { return points.size(); }
|
||||
static Eigen::Vector4d point(const std::vector<Point>& points, size_t i) {
|
||||
if constexpr (std::is_same_v<Scalar, double>) {
|
||||
if constexpr (D == 3) {
|
||||
return points[i].homogeneous();
|
||||
} else {
|
||||
return points[i];
|
||||
}
|
||||
} else {
|
||||
if constexpr (D == 3) {
|
||||
return points[i].homogeneous().template cast<double>();
|
||||
} else {
|
||||
return points[i].template cast<double>();
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
} // namespace traits
|
||||
} // namespace small_gicp
|
||||
|
|
@ -108,7 +108,7 @@ struct LevenbergMarquardtOptimizer {
|
|||
// Solve with damping
|
||||
const Eigen::Matrix<double, 6, 1> delta = (H + lambda * Eigen::Matrix<double, 6, 6>::Identity()).ldlt().solve(-b);
|
||||
|
||||
// Validte new solution
|
||||
// Validate new solution
|
||||
const Eigen::Isometry3d new_T = result.T_target_source * se3_exp(delta);
|
||||
double new_e = reduction.error(target, source, new_T, factors);
|
||||
general_factor.update_error(target, source, new_T, &e);
|
||||
|
|
@ -124,6 +124,7 @@ struct LevenbergMarquardtOptimizer {
|
|||
result.T_target_source = new_T;
|
||||
lambda /= lambda_factor;
|
||||
success = true;
|
||||
e = new_e;
|
||||
|
||||
break;
|
||||
} else {
|
||||
|
|
|
|||
|
|
@ -7,7 +7,11 @@
|
|||
namespace small_gicp {
|
||||
|
||||
#ifndef _OPENMP
|
||||
#ifdef _WIN32
|
||||
#pragma message(__FILE__, " OpenMP is not available.Parallel reduction will be disabled.")
|
||||
#else
|
||||
#warning "OpenMP is not available. Parallel reduction will be disabled."
|
||||
#endif
|
||||
inline int omp_get_thread_num() {
|
||||
return 0;
|
||||
}
|
||||
|
|
|
|||
|
|
@ -33,6 +33,8 @@ void define_align(py::module& m) {
|
|||
double max_correspondence_distance,
|
||||
int num_threads,
|
||||
int max_iterations,
|
||||
double rotation_epsilon,
|
||||
double translation_epsilon,
|
||||
bool verbose) {
|
||||
if (target_points.cols() != 3 && target_points.cols() != 4) {
|
||||
std::cerr << "target_points must be Nx3 or Nx4" << std::endl;
|
||||
|
|
@ -62,6 +64,8 @@ void define_align(py::module& m) {
|
|||
setting.max_correspondence_distance = max_correspondence_distance;
|
||||
setting.num_threads = num_threads;
|
||||
setting.max_iterations = max_iterations;
|
||||
setting.rotation_eps = rotation_epsilon;
|
||||
setting.translation_eps = translation_epsilon;
|
||||
setting.verbose = verbose;
|
||||
|
||||
std::vector<Eigen::Vector4d> target(target_points.rows());
|
||||
|
|
@ -97,6 +101,8 @@ void define_align(py::module& m) {
|
|||
py::arg("max_correspondence_distance") = 1.0,
|
||||
py::arg("num_threads") = 1,
|
||||
py::arg("max_iterations") = 20,
|
||||
py::arg("rotation_epsilon") = 0.1 * M_PI / 180.0,
|
||||
py::arg("translation_epsilon") = 1e-3,
|
||||
py::arg("verbose") = false,
|
||||
R"pbdoc(
|
||||
Align two point clouds using various ICP-like algorithms.
|
||||
|
|
@ -125,6 +131,10 @@ void define_align(py::module& m) {
|
|||
Number of threads to use for parallel processing.
|
||||
max_iterations : int = 20
|
||||
Maximum number of iterations for the optimization algorithm.
|
||||
rotation_epsilon: double = 0.1 * M_PI / 180.0
|
||||
Convergence criteria for rotation change
|
||||
translation_epsilon: double = 1e-3
|
||||
Convergence criteria for transformation change
|
||||
verbose : bool = False
|
||||
If True, print debug information during the optimization process.
|
||||
|
||||
|
|
@ -146,6 +156,8 @@ void define_align(py::module& m) {
|
|||
double max_correspondence_distance,
|
||||
int num_threads,
|
||||
int max_iterations,
|
||||
double rotation_epsilon,
|
||||
double translation_epsilon,
|
||||
bool verbose) {
|
||||
RegistrationSetting setting;
|
||||
if (registration_type == "ICP") {
|
||||
|
|
@ -161,6 +173,8 @@ void define_align(py::module& m) {
|
|||
setting.max_correspondence_distance = max_correspondence_distance;
|
||||
setting.num_threads = num_threads;
|
||||
setting.max_iterations = max_iterations;
|
||||
setting.rotation_eps = rotation_epsilon;
|
||||
setting.translation_eps = translation_epsilon;
|
||||
setting.verbose = verbose;
|
||||
|
||||
if (target_tree == nullptr) {
|
||||
|
|
@ -176,6 +190,8 @@ void define_align(py::module& m) {
|
|||
py::arg("max_correspondence_distance") = 1.0,
|
||||
py::arg("num_threads") = 1,
|
||||
py::arg("max_iterations") = 20,
|
||||
py::arg("rotation_epsilon") = 0.1 * M_PI / 180.0,
|
||||
py::arg("translation_epsilon") = 1e-3,
|
||||
py::arg("verbose") = false,
|
||||
R"pbdoc(
|
||||
Align two point clouds using specified ICP-like algorithms, utilizing point cloud and KD-tree inputs.
|
||||
|
|
@ -200,6 +216,10 @@ void define_align(py::module& m) {
|
|||
Number of threads to use for computation.
|
||||
max_iterations : int = 20
|
||||
Maximum number of iterations for the optimization algorithm.
|
||||
rotation_epsilon: double = 0.1 * M_PI / 180.0
|
||||
Convergence criteria for rotation change
|
||||
translation_epsilon: double = 1e-3
|
||||
Convergence criteria for transformation change
|
||||
verbose : bool = False
|
||||
If True, print debug information during the optimization process.
|
||||
|
||||
|
|
@ -219,11 +239,15 @@ void define_align(py::module& m) {
|
|||
double max_correspondence_distance,
|
||||
int num_threads,
|
||||
int max_iterations,
|
||||
double rotation_epsilon,
|
||||
double translation_epsilon,
|
||||
bool verbose) {
|
||||
Registration<GICPFactor, ParallelReductionOMP> registration;
|
||||
registration.rejector.max_dist_sq = max_correspondence_distance * max_correspondence_distance;
|
||||
registration.reduction.num_threads = num_threads;
|
||||
registration.optimizer.max_iterations = max_iterations;
|
||||
registration.criteria.rotation_eps = rotation_epsilon;
|
||||
registration.criteria.translation_eps = translation_epsilon;
|
||||
registration.optimizer.verbose = verbose;
|
||||
|
||||
return registration.align(target_voxelmap, source, target_voxelmap, Eigen::Isometry3d(init_T_target_source));
|
||||
|
|
@ -234,6 +258,8 @@ void define_align(py::module& m) {
|
|||
py::arg("max_correspondence_distance") = 1.0,
|
||||
py::arg("num_threads") = 1,
|
||||
py::arg("max_iterations") = 20,
|
||||
py::arg("rotation_epsilon") = 0.1 * M_PI / 180.0,
|
||||
py::arg("translation_epsilon") = 1e-3,
|
||||
py::arg("verbose") = false,
|
||||
R"pbdoc(
|
||||
Align two point clouds using voxel-based GICP algorithm, utilizing a Gaussian Voxel Map.
|
||||
|
|
@ -254,6 +280,10 @@ void define_align(py::module& m) {
|
|||
Number of threads to use for computation.
|
||||
max_iterations : int = 20
|
||||
Maximum number of iterations for the optimization algorithm.
|
||||
rotation_epsilon: double = 0.1 * M_PI / 180.0
|
||||
Convergence criteria for rotation change
|
||||
translation_epsilon: double = 1e-3
|
||||
Convergence criteria for transformation change
|
||||
verbose : bool = False
|
||||
If True, print debug information during the optimization process.
|
||||
|
||||
|
|
|
|||
|
|
@ -129,7 +129,7 @@ void define_kdtree(py::module& m) {
|
|||
std::vector<size_t> k_indices(pts.rows(), -1);
|
||||
std::vector<double> k_sq_dists(pts.rows(), std::numeric_limits<double>::max());
|
||||
|
||||
#pragma omp parallel for num_threads(num_threads)
|
||||
#pragma omp parallel for num_threads(num_threads) schedule(guided, 4)
|
||||
for (int i = 0; i < pts.rows(); ++i) {
|
||||
const size_t found = traits::nearest_neighbor_search(kdtree, Eigen::Vector4d(pts(i, 0), pts(i, 1), pts(i, 2), 1.0), &k_indices[i], &k_sq_dists[i]);
|
||||
if (!found) {
|
||||
|
|
@ -154,9 +154,9 @@ void define_kdtree(py::module& m) {
|
|||
|
||||
Returns
|
||||
-------
|
||||
k_indices : numpy.ndarray, shape (n,)
|
||||
k_indices : numpy.ndarray, shape (n, k)
|
||||
The indices of the nearest neighbors for each input point. If a neighbor was not found, the index is -1.
|
||||
k_sq_dists : numpy.ndarray, shape (n,)
|
||||
k_sq_dists : numpy.ndarray, shape (n, k)
|
||||
The squared distances to the nearest neighbors for each input point.
|
||||
)""")
|
||||
|
||||
|
|
@ -167,16 +167,21 @@ void define_kdtree(py::module& m) {
|
|||
throw std::invalid_argument("pts must have shape (n, 3) or (n, 4)");
|
||||
}
|
||||
|
||||
std::vector<std::vector<size_t>> k_indices(pts.rows(), std::vector<size_t>(k, -1));
|
||||
std::vector<std::vector<double>> k_sq_dists(pts.rows(), std::vector<double>(k, std::numeric_limits<double>::max()));
|
||||
Eigen::Matrix<size_t, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> k_indices(pts.rows(), k);
|
||||
Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> k_sq_dists(pts.rows(), k);
|
||||
k_indices.setConstant(-1);
|
||||
k_sq_dists.setConstant(std::numeric_limits<double>::max());
|
||||
|
||||
#pragma omp parallel for num_threads(num_threads)
|
||||
#pragma omp parallel for num_threads(num_threads) schedule(guided, 4)
|
||||
for (int i = 0; i < pts.rows(); ++i) {
|
||||
const size_t found = traits::knn_search(kdtree, Eigen::Vector4d(pts(i, 0), pts(i, 1), pts(i, 2), 1.0), k, k_indices[i].data(), k_sq_dists[i].data());
|
||||
size_t* k_indices_begin = k_indices.data() + i * k;
|
||||
double* k_sq_dists_begin = k_sq_dists.data() + i * k;
|
||||
|
||||
const size_t found = traits::knn_search(kdtree, Eigen::Vector4d(pts(i, 0), pts(i, 1), pts(i, 2), 1.0), k, k_indices_begin, k_sq_dists_begin);
|
||||
if (found < k) {
|
||||
for (size_t j = found; j < k; ++j) {
|
||||
k_indices[i][j] = -1;
|
||||
k_sq_dists[i][j] = std::numeric_limits<double>::max();
|
||||
k_indices_begin[j] = -1;
|
||||
k_sq_dists_begin[j] = std::numeric_limits<double>::max();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
|||
Loading…
Reference in New Issue