![]() |
small_gicp package from small_gicp reposmall_gicp |
Package Summary
Tags | No category tags. |
Version | 1.0.0 |
License | MIT |
Build type | CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/koide3/small_gicp.git |
VCS Type | git |
VCS Version | master |
Last Updated | 2025-01-12 |
Dev Status | UNMAINTAINED |
CI status | No Continuous Integration |
Released | UNRELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Kenji Koide
Authors
small_gicp
small_gicp is a header-only C++ library providing efficient and parallelized algorithms for fine point cloud registration (ICP, Point-to-Plane ICP, GICP, VGICP, etc.). It is a refined and optimized version of its predecessor, fast_gicp, re-written from scratch with the following features.
- Highly Optimized : The core registration algorithm implementation has been further optimized from fast_gicp, achieving up to 2x speed gain.
- Fully parallerized : small_gicp offers parallel implementations of several preprocessing algorithms, making the entire registration process parallelized (e.g., Downsampling, KdTree construction, Normal/Covariance estimation). It supports OpenMP and Intel TBB as parallelism backends.
- Minimum dependencies : The library requires only Eigen along with the bundled nanoflann and Sophus. Optionally, it supports a PCL registration interface for use as a drop-in replacement
- Customizable : small_gicp allows the integration of any custom point cloud class into the registration algorithm via traits. Its template-based implementation enables customization of the registration process with original correspondence estimators and registration factors.
- Python bindings : By being isolated from PCL, small_gicp’s Python bindings are more portable and can be used seamlessly with other libraries such as Open3D.
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. It would help the author receive recognition in his organization and keep working on this project. Please also cite the corresponding software paper if you use this software in an academic work.
Requirements
This library uses C++17 features. The PCL interface is not compatible with PCL older than 1.11 that uses boost::shared_ptr
.
Dependencies
Installation
C++
small_gicp is a header-only library. You can just download and drop it in your project directory to use it.
If you need only basic point cloud registration functions, you can build and install the helper library as follows.
sudo apt-get install libeigen3-dev libomp-dev
cd small_gicp
mkdir build && cd build
cmake .. -DCMAKE_BUILD_TYPE=Release && make -j
sudo make install
Python (Linux / Windows / MacOS)
Install from PyPI
pip install small_gicp
Install from source
cd small_gicp
pip install .
# [Optional (linux)] Install stubs for autocomplete (If you know a better way, let me know...)
pip install pybind11-stubgen
cd ~/.local/lib/python3.10/site-packages
pybind11-stubgen -o . --ignore-invalid=all small_gicp
Documentation
Usage (C++)
The following examples assume using namespace small_gicp
is placed somewhere.
Using helper library (01_basic_registration.cpp)
The helper library (registration_helper.hpp
) enables easily processing point clouds represented as std::vector<Eigen::Vector(3|4)(f|d)>
.
Expand
`small_gicp::align` takes two point clouds (`std::vectors` of `Eigen::Vector(3|4)(f|d)`) and returns a registration result (estimated transformation and some information on the optimization result). This is the easiest way to use small_gicp but causes an overhead for duplicated preprocessing. ```cpp #include <small_gicp/registration/registration_helper.hpp> std::vector<Eigen::Vector3d> target_points = ...; // Any of Eigen::Vector(3|4)(f|d) can be used std::vector<Eigen::Vector3d> source_points = ...; // RegistrationSetting setting; setting.num_threads = 4; // Number of threads to be used setting.downsampling_resolution = 0.25; // Downsampling resolution setting.max_correspondence_distance = 1.0; // Maximum correspondence distance between points (e.g., triming threshold) Eigen::Isometry3d init_T_target_source = Eigen::Isometry3d::Identity(); RegistrationResult result = align(target_points, source_points, init_T_target_source, setting); Eigen::Isometry3d T = result.T_target_source; // Estimated transformation size_t num_inliers = result.num_inliers; // Number of inlier source points Eigen::Matrix<double, 6, 6> H = result.H; // Final Hessian matrix (6x6) ``` There is also a way to perform preprocessing and registration separately. This enables saving time for preprocessing in case registration is performed several times for the same point cloud (e.g., typical odometry estimation based on scan-to-scan matching). ```cpp #include <small_gicp/registration/registration_helper.hpp> std::vector<Eigen::Vector3d> target_points = ...; // Any of Eigen::Vector(3|4)(f|d) can be used std::vector<Eigen::Vector3d> source_points = ...; // int num_threads = 4; // Number of threads to be used double downsampling_resolution = 0.25; // Downsampling resolution int num_neighbors = 10; // Number of neighbor points used for normal and covariance estimation // std::pair<PointCloud::Ptr, KdTreeExpand
```cpp #include <small_gicp/pcl/pcl_registration.hpp> pcl::PointCloud<pcl::PointXYZ>::Ptr raw_target = ...; pcl::PointCloud<pcl::PointXYZ>::Ptr raw_source = ...; // small_gicp::voxelgrid_downsampling can directly operate on pcl::PointCloud. pcl::PointCloud<pcl::PointXYZ>::Ptr target = voxelgrid_sampling_omp(*raw_target, 0.25); pcl::PointCloud<pcl::PointXYZ>::Ptr source = voxelgrid_sampling_omp(*raw_source, 0.25); // RegistrationPCL is derived from pcl::Registration and has mostly the same interface as pcl::GeneralizedIterativeClosestPoint. RegistrationPCL<pcl::PointXYZ, pcl::PointXYZ> reg; reg.setNumThreads(4); reg.setCorrespondenceRandomness(20); reg.setMaxCorrespondenceDistance(1.0); reg.setVoxelResolution(1.0); reg.setRegistrationType("VGICP"); // or "GICP" (default = "GICP") // Set input point clouds. reg.setInputTarget(target); reg.setInputSource(source); // Align point clouds. auto aligned = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(); reg.align(*aligned); // Swap source and target and align again. // This is useful when you want to re-use preprocessed point clouds for successive registrations (e.g., odometry estimation). reg.swapSourceAndTarget(); reg.align(*aligned); ``` It is also possible to directly feed `pcl::PointCloud` to `small_gicp::Registration`. Because all preprocessed data are exposed in this way, you can easily re-use them to obtain the best efficiency. ```cpp #include <small_gicp/pcl/pcl_point.hpp> #include <small_gicp/pcl/pcl_point_traits.hpp> pcl::PointCloud<pcl::PointXYZ>::Ptr raw_target = ...; pcl::PointCloud<pcl::PointXYZ>::Ptr raw_source = ...; // Downsample points and convert them into pcl::PointCloud<pcl::PointCovariance>. pcl::PointCloud<pcl::PointCovariance>::Ptr target = voxelgrid_sampling_omp<pcl::PointCloud<pcl::PointXYZ>, pcl::PointCloud<pcl::PointCovariance>>(*raw_target, 0.25); pcl::PointCloud<pcl::PointCovariance>::Ptr source = voxelgrid_sampling_omp<pcl::PointCloud<pcl::PointXYZ>, pcl::PointCloud<pcl::PointCovariance>>(*raw_source, 0.25); // Estimate covariances of points. const int num_threads = 4; const int num_neighbors = 20; estimate_covariances_omp(*target, num_neighbors, num_threads); estimate_covariances_omp(*source, num_neighbors, num_threads); // Create KdTree for target and source. auto target_tree = std::make_shared<KdTree<pcl::PointCloud<pcl::PointCovariance>>>(target, KdTreeBuilderOMP(num_threads)); auto source_tree = std::make_shared<KdTree<pcl::PointCloud<pcl::PointCovariance>>>(source, KdTreeBuilderOMP(num_threads)); Registration<GICPFactor, ParallelReductionOMP> registration; registration.reduction.num_threads = num_threads; registration.rejector.max_dist_sq = 1.0; // Align point clouds. Note that the input point clouds are pcl::PointCloud<pcl::PointCovariance>. auto result = registration.align(*target, *source, *target_tree, Eigen::Isometry3d::Identity()); ```Expand
```cpp #include <small_gicp/ann/kdtree_omp.hpp> #include <small_gicp/points/point_cloud.hpp> #include <small_gicp/factors/gicp_factor.hpp> #include <small_gicp/util/normal_estimation_omp.hpp> #include <small_gicp/registration/reduction_omp.hpp> #include <small_gicp/registration/registration.hpp> std::vector<Eigen::Vector3d> target_points = ...; // Any of Eigen::Vector(3|4)(f|d) can be used std::vector<Eigen::Vector3d> source_points = ...; // int num_threads = 4; double downsampling_resolution = 0.25; int num_neighbors = 10; double max_correspondence_distance = 1.0; // Convert to small_gicp::PointCloud auto target = std::make_sharedExpand
Example A : Perform registration with numpy arrays ```python # Align two point clouds using various ICP-like algorithms. # # Parameters # ---------- # target_points : NDArray[np.float64] # Nx3 or Nx4 matrix representing the target point cloud. # source_points : NDArray[np.float64] # Nx3 or Nx4 matrix representing the source point cloud. # init_T_target_source : np.ndarray[np.float64] # 4x4 matrix representing the initial transformation from target to source. # registration_type : str = 'GICP' # Type of registration algorithm to use ('ICP', 'PLANE_ICP', 'GICP', 'VGICP'). # voxel_resolution : float = 1.0 # Resolution of voxels used for correspondence search (used only in VGICP). # downsampling_resolution : float = 0.25 # Resolution for downsampling the point clouds. # max_correspondence_distance : float = 1.0 # Maximum distance for matching points between point clouds. # num_threads : int = 1 # Number of threads to use for parallel processing. # # Returns # ------- # RegistrationResult # Object containing the final transformation matrix and convergence status. result = small_gicp.align(target_raw_numpy, source_raw_numpy, downsampling_resolution=0.25) result.T_target_source # Estimated transformation (4x4 numpy array) result.converged # If true, the optimization converged successfully result.iterations # Number of iterations the optimization took result.num_inliers # Number of inlier points result.H # Final Hessian matrix (6x6 matrix) result.b # Final information vector (6D vector) result.e # Final error (float) ``` Example B : Perform preprocessing and registration separately ```python # Preprocess point cloud (downsampling, kdtree construction, and normal/covariance estimation) # # Parameters # ---------- # points : NDArray[np.float64] # Nx3 or Nx4 matrix representing the point cloud. # downsampling_resolution : float = 0.1 # Resolution for downsampling the point clouds. # num_neighbors : int = 20 # Number of neighbor points to usefor point normal/covariance estimation. # num_threads : int = 1 # Number of threads to use for parallel processing. # # Returns # ------- # PointCloud # Downsampled point cloud with estimated normals and covariances. # KdTree # KdTree for the downsampled point cloud target, target_tree = small_gicp.preprocess_points(target_raw_numpy, downsampling_resolution=0.25) source, source_tree = small_gicp.preprocess_points(source_raw_numpy, downsampling_resolution=0.25) # `target` and `source` are small_gicp.PointCloud with the following methods target.size() # Number of points target.points() # Nx4 numpy array [x, y, z, 1] x N target.normals() # Nx4 numpy array [nx, ny, nz, 0] x N target.covs() # Array of 4x4 covariance matrices # Align two point clouds using specified ICP-like algorithms, utilizing point cloud and KD-tree inputs. # # Parameters # ---------- # target : PointCloud::ConstPtr # Pointer to the target point cloud. # source : PointCloud::ConstPtr # Pointer to the source point cloud. # target_tree : KdTreeWiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
cmake |
eigen |
libomp-dev |