Skip to main content

Efficient and parallelized algorithms for fine point cloud registration

Project description

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.

Build(Linux) macos Build(Windows) Test codecov

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.

#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).

#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, KdTree<PointCloud>::Ptr>
auto [target, target_tree] = preprocess_points(target_points, downsampling_resolution, num_neighbors, num_threads);
auto [source, source_tree] = preprocess_points(source_points, downsampling_resolution, num_neighbors, num_threads);

RegistrationSetting setting;
setting.num_threads = num_threads;
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, *source, *target_tree, 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)

Using PCL interface (02_basic_registration_pcl.cpp)

The PCL interface allows using small_gicp as a drop-in replacement for pcl::Registration. It is also possible to directly feed pcl::PointCloud to algorithms implemented in small_gicp.

Expand
#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.

#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());

Using Registration template (03_registration_template.cpp)

If you want to fine-control and customize the registration process, use small_gicp::Registration template that allows modifying the inner algorithms and parameters.

Expand
#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_shared<PointCloud>(target_points);
auto source = std::make_shared<PointCloud>(source_points);

// Downsampling
target = voxelgrid_sampling_omp(*target, downsampling_resolution, num_threads);
source = voxelgrid_sampling_omp(*source, downsampling_resolution, num_threads);

// Create KdTree
auto target_tree = std::make_shared<KdTree<PointCloud>>(target, KdTreeBuilderOMP(num_threads));
auto source_tree = std::make_shared<KdTree<PointCloud>>(source, KdTreeBuilderOMP(num_threads));

// Estimate point covariances
estimate_covariances_omp(*target, *target_tree, num_neighbors, num_threads);
estimate_covariances_omp(*source, *source_tree, num_neighbors, num_threads);

// GICP + OMP-based parallel reduction
Registration<GICPFactor, ParallelReductionOMP> registration;
registration.reduction.num_threads = num_threads;
registration.rejector.max_dist_sq = max_correspondence_distance * max_correspondence_distance;

// Align point clouds
Eigen::Isometry3d init_T_target_source = Eigen::Isometry3d::Identity();
auto result = registration.align(*target, *source, *target_tree, init_T_target_source);

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)

See 03_registration_template.cpp for more detailed customization examples.

Cookbook

Usage (Python) basic_registration.py

Expand

Example A : Perform registration with numpy arrays

# 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

# 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 : KdTree<PointCloud>::ConstPtr, optional
#      Pointer to the KD-tree of the target for nearest neighbor search. If nullptr, a new tree is built.
#  init_T_target_source : 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').
#  max_correspondence_distance : float = 1.0
#      Maximum distance for corresponding point pairs.
#  num_threads : int = 1
#      Number of threads to use for computation.
# 
#  Returns
#  -------
#  RegistrationResult
#      Object containing the final transformation matrix and convergence status.
result = small_gicp.align(target, source, target_tree)

Example C : Perform each of preprocessing steps one-by-one

# Convert numpy arrays (Nx3 or Nx4) to small_gicp.PointCloud
target_raw = small_gicp.PointCloud(target_raw_numpy)
source_raw = small_gicp.PointCloud(source_raw_numpy)

# Downsampling
target = small_gicp.voxelgrid_sampling(target_raw, 0.25)
source = small_gicp.voxelgrid_sampling(source_raw, 0.25)

# KdTree construction
target_tree = small_gicp.KdTree(target)
source_tree = small_gicp.KdTree(source)

# Estimate covariances
small_gicp.estimate_covariances(target, target_tree)
small_gicp.estimate_covariances(source, source_tree)

# Align point clouds
result = small_gicp.align(target, source, target_tree)

Example D: Example with Open3D

target_o3d = open3d.io.read_point_cloud('small_gicp/data/target.ply').paint_uniform_color([0, 1, 0])
source_o3d = open3d.io.read_point_cloud('small_gicp/data/source.ply').paint_uniform_color([0, 0, 1])

target, target_tree = small_gicp.preprocess_points(numpy.asarray(target_o3d.points), downsampling_resolution=0.25)
source, source_tree = small_gicp.preprocess_points(numpy.asarray(source_o3d.points), downsampling_resolution=0.25)
result = small_gicp.align(target, source, target_tree)

source_o3d.transform(result.T_target_source)
open3d.visualization.draw_geometries([target_o3d, source_o3d])

Cookbook

Running examples

C++

cd small_gicp
mkdir build && cd build
cmake .. -DBUILD_EXAMPLES=ON && make -j

cd ..
./build/01_basic_registration
./build/02_basic_registration_pcl
./build/03_registration_template

Python

cd small_gicp
pip install .

python3 src/example/basic_registration.py

Benchmark

Processing speed comparison between small_gicp and Open3D (youtube). small_comp

Downsampling

  • 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 provides accurate downsampling results that are nearly identical to those of pcl::VoxelGrid, while pcl::ApproximateVoxelGrid can produce spurious points (up to 2x more points).
  • small_gicp::voxelgrid_sampling can handle larger point clouds with finer voxel resolutions compared to pcl::VoxelGrid. For a point cloud with a width of 1000m, the minimum voxel resolution can be 0.5 mm.

downsampling_comp

KdTree construction

  • Multi-threaded implementation (TBB and OMP) can be up to 6x faster than the single-threaded version. The single-thread version performs almost equivalently to nanoflann.
  • The new KdTree implementation demonstrates good scalability due to its well-balanced task assignment.
  • This benchmark compares only the construction time (query time is not included). Nearest neighbor queries are included and evaluated in the following odometry estimation evaluation.

kdtree_time

Odometry estimation

  • Single-thread small_gicp::GICP is about 2.4x and 1.9x faster than pcl::GICP and fast_gicp::GICP, respectively.
  • small_gicp::(GICP|VGICP) demonstrates better multi-threaded scalability compared to fast_gicp::(GICP|VGICP).
  • small_gicp::GICP parallelized with TBB flow graph shows excellent scalability in many-threads scenarios (~128 threads), though with some latency degradation.
  • Outputs of small_gicp::GICP are almost identical to those of fast_gicp::GICP.

odometry_time

License

This package is released under the MIT license.

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.

Contact

Kenji Koide, National Institute of Advanced Industrial Science and Technology (AIST)

Project details


Download files

Download the file for your platform. If you're not sure which to choose, learn more about installing packages.

Source Distribution

small_gicp-0.1.3.tar.gz (2.6 MB view details)

Uploaded Source

Built Distributions

small_gicp-0.1.3-cp312-abi3-win_amd64.whl (223.0 kB view details)

Uploaded CPython 3.12+ Windows x86-64

small_gicp-0.1.3-cp312-abi3-manylinux_2_28_x86_64.whl (337.4 kB view details)

Uploaded CPython 3.12+ manylinux: glibc 2.28+ x86-64

small_gicp-0.1.3-cp312-abi3-manylinux_2_28_aarch64.whl (313.2 kB view details)

Uploaded CPython 3.12+ manylinux: glibc 2.28+ ARM64

small_gicp-0.1.3-cp312-abi3-macosx_11_0_arm64.whl (434.6 kB view details)

Uploaded CPython 3.12+ macOS 11.0+ ARM64

small_gicp-0.1.3-cp311-cp311-win_amd64.whl (221.2 kB view details)

Uploaded CPython 3.11 Windows x86-64

small_gicp-0.1.3-cp311-cp311-manylinux_2_28_x86_64.whl (339.2 kB view details)

Uploaded CPython 3.11 manylinux: glibc 2.28+ x86-64

small_gicp-0.1.3-cp311-cp311-manylinux_2_28_aarch64.whl (315.4 kB view details)

Uploaded CPython 3.11 manylinux: glibc 2.28+ ARM64

small_gicp-0.1.3-cp311-cp311-macosx_11_0_arm64.whl (434.4 kB view details)

Uploaded CPython 3.11 macOS 11.0+ ARM64

small_gicp-0.1.3-cp310-cp310-win_amd64.whl (220.2 kB view details)

Uploaded CPython 3.10 Windows x86-64

small_gicp-0.1.3-cp310-cp310-manylinux_2_28_x86_64.whl (337.3 kB view details)

Uploaded CPython 3.10 manylinux: glibc 2.28+ x86-64

small_gicp-0.1.3-cp310-cp310-manylinux_2_28_aarch64.whl (313.6 kB view details)

Uploaded CPython 3.10 manylinux: glibc 2.28+ ARM64

small_gicp-0.1.3-cp310-cp310-macosx_11_0_arm64.whl (433.1 kB view details)

Uploaded CPython 3.10 macOS 11.0+ ARM64

small_gicp-0.1.3-cp39-cp39-win_amd64.whl (216.5 kB view details)

Uploaded CPython 3.9 Windows x86-64

small_gicp-0.1.3-cp39-cp39-manylinux_2_28_x86_64.whl (338.7 kB view details)

Uploaded CPython 3.9 manylinux: glibc 2.28+ x86-64

small_gicp-0.1.3-cp39-cp39-manylinux_2_28_aarch64.whl (313.7 kB view details)

Uploaded CPython 3.9 manylinux: glibc 2.28+ ARM64

small_gicp-0.1.3-cp39-cp39-macosx_11_0_arm64.whl (433.1 kB view details)

Uploaded CPython 3.9 macOS 11.0+ ARM64

small_gicp-0.1.3-cp38-cp38-win_amd64.whl (220.2 kB view details)

Uploaded CPython 3.8 Windows x86-64

small_gicp-0.1.3-cp38-cp38-manylinux_2_28_x86_64.whl (338.3 kB view details)

Uploaded CPython 3.8 manylinux: glibc 2.28+ x86-64

small_gicp-0.1.3-cp38-cp38-manylinux_2_28_aarch64.whl (313.6 kB view details)

Uploaded CPython 3.8 manylinux: glibc 2.28+ ARM64

small_gicp-0.1.3-cp38-cp38-macosx_11_0_arm64.whl (432.9 kB view details)

Uploaded CPython 3.8 macOS 11.0+ ARM64

File details

Details for the file small_gicp-0.1.3.tar.gz.

File metadata

  • Download URL: small_gicp-0.1.3.tar.gz
  • Upload date:
  • Size: 2.6 MB
  • Tags: Source
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/5.1.0 CPython/3.12.4

File hashes

Hashes for small_gicp-0.1.3.tar.gz
Algorithm Hash digest
SHA256 ff3cb4b963d41384d741d73dca99eb6a215ceefaaec62050a3b388097b0197c8
MD5 bee0f822b19fd1796679d1abb6bfffa5
BLAKE2b-256 c048307bd538a448f7d3e685114c162e558877e0c6908a6f9f5dd6197d1d14a1

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp312-abi3-win_amd64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp312-abi3-win_amd64.whl
Algorithm Hash digest
SHA256 8f31bb6647631940cdec68da899a928e72fb5a40493c1395ac8dd2c73d00f67e
MD5 f055284668582810a4055eecd9e328fd
BLAKE2b-256 5f06a35d0ff34824d9dc32c75b88fc7579a432cce5a75623fe78c305083113e7

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp312-abi3-manylinux_2_28_x86_64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp312-abi3-manylinux_2_28_x86_64.whl
Algorithm Hash digest
SHA256 0db5fb6f3ce7cc58fdea8f3c050b262cde5d1c520ee3362a122cefd26f55c466
MD5 873d6979652dcaeeb8417f89b6b3fe0c
BLAKE2b-256 b5399d46a454e5885be53892915efe50bdcae967cc65b5013c79022dd10f44de

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp312-abi3-manylinux_2_28_aarch64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp312-abi3-manylinux_2_28_aarch64.whl
Algorithm Hash digest
SHA256 2c63f137783aae2f30150ba7c97d3973468e6d35f9432d5b24fb3e3ad56ff5df
MD5 e19c5ca4b73a5edbe9662b0aae0abe52
BLAKE2b-256 f19fe48fd96f0e29044861c627f75f8d19856f0724e75b9fd2a216ac6c90c2ad

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp312-abi3-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp312-abi3-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 417e06fb21035f166eea171221fc8cb4cb953547c3dbbf14a02f46b160a80c98
MD5 ba72d0a6c7adbae41e525559fcc73f38
BLAKE2b-256 3098039b779e383bdaae4bb05681b010a6970a4aecef65f4ee14dae336f46f64

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp311-cp311-win_amd64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp311-cp311-win_amd64.whl
Algorithm Hash digest
SHA256 18c395defb662b9d81e94b9ae42683dbe6a3975cb07c1f2c8a31e5749445a511
MD5 f00a0eed07c82c86ad63c1d8008a5224
BLAKE2b-256 cbcb2b00928071e923a1ce8767770926952a8592a540344ba65b15e386e2d6df

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp311-cp311-manylinux_2_28_x86_64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp311-cp311-manylinux_2_28_x86_64.whl
Algorithm Hash digest
SHA256 080c11aaf5d81a7a3db04157b4af1313938ff33da81019b10a6bb1a086f7cd86
MD5 0336c3d9416d46ebdfbd5495d16215a7
BLAKE2b-256 9e11e9e5d59d0c97d13c8dc5a197ecf76e5b931f0fdb55a671548284fc44d458

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp311-cp311-manylinux_2_28_aarch64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp311-cp311-manylinux_2_28_aarch64.whl
Algorithm Hash digest
SHA256 0660393fe6c10c368a3db12b483ea92355b80f9291d40798a041e400c5e72432
MD5 82dd08498f79de2341092502bca76c70
BLAKE2b-256 21b1f60357cd3acaf3a04dba2a207aa34ef4c3ac300309280804beecaa579bfa

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp311-cp311-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp311-cp311-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 d84c73585abee3b319b4e8f031a5c4ecc245855f66707e7dfe2d2c23aac66a47
MD5 3f0f737ff0bde5c61e214f4e25a48c2f
BLAKE2b-256 936d7a31ae34c4b517d2eaeb8487f2db18fa9d352895ea3d46a4071dd0639626

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp310-cp310-win_amd64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp310-cp310-win_amd64.whl
Algorithm Hash digest
SHA256 77eb6d7365b1bcbe1c431db0bf15b5bed719feb9d699e9598e944514c3901978
MD5 3b7af1a05c5fafa847f1d6c78b4aef4b
BLAKE2b-256 292942e344207e4363e9d554c4c4f0ce2592ca08de3d5b8809dd6bec53d7155c

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp310-cp310-manylinux_2_28_x86_64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp310-cp310-manylinux_2_28_x86_64.whl
Algorithm Hash digest
SHA256 388eae25cfb2fd608aaf074265008231d94c04d59e7e3d3edb28c4df8781827a
MD5 c1055956b31cb2b354ecd2b17bdbd630
BLAKE2b-256 484b007615f39d69ad2faf8aacb59aa135a8feff96bf86c93823a0eac1bff182

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp310-cp310-manylinux_2_28_aarch64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp310-cp310-manylinux_2_28_aarch64.whl
Algorithm Hash digest
SHA256 6985fd0e9aa6f11e7258bb70f81dc36c0eee6ede822de0212d098c280191ea24
MD5 dbba40b50e514a32ff140e7f08339314
BLAKE2b-256 086859864fb42220067ef72198e56287f84c8c7e43fad122e24a6866983f44c7

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp310-cp310-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp310-cp310-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 1b15ee8aef67daa3b5e63e425a113ef9fb232cda5f6f29add7854b723418bfd1
MD5 4af7c44b74132139debaf9735f5c5f9d
BLAKE2b-256 69434b8deb1566c821349ff0f078fd3f8abf42f7437fadd40bafa628044e4ca7

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp39-cp39-win_amd64.whl.

File metadata

  • Download URL: small_gicp-0.1.3-cp39-cp39-win_amd64.whl
  • Upload date:
  • Size: 216.5 kB
  • Tags: CPython 3.9, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/5.1.0 CPython/3.12.4

File hashes

Hashes for small_gicp-0.1.3-cp39-cp39-win_amd64.whl
Algorithm Hash digest
SHA256 cfdbc32a5278299b75f2ff76304885e055d7588742993a6f9639d7f19938234a
MD5 d0b0c7aaaee6be0b9e9b3569cb3c0ff5
BLAKE2b-256 08fa225db56660e0c187af34d51664f9338d967e2892c35c677fa2a35a9c0044

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp39-cp39-manylinux_2_28_x86_64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp39-cp39-manylinux_2_28_x86_64.whl
Algorithm Hash digest
SHA256 9153dbbca8f6bb49083b054566bef2c2459960509640863e50f677935ff827d1
MD5 2bea33eef92608dd806d26599c23adff
BLAKE2b-256 570021d46443df695764d914c0fea99ec63fa5e483f22b668fd6d3b83ce7842a

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp39-cp39-manylinux_2_28_aarch64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp39-cp39-manylinux_2_28_aarch64.whl
Algorithm Hash digest
SHA256 7a5ec75dde06ae939dbcd109cad92ed68bad419e0409dad581e858162c451ece
MD5 34a4b8bf8f0272d3e9321ee33a3741be
BLAKE2b-256 e9970b6765cb8569600d0d7e210ebbd56c2e84b96cb5baac35662f9c90bce2d2

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp39-cp39-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp39-cp39-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 0edf374a764c43b19fa300f41ad2021e82b76dc8f7971d318fe536acb9c7694b
MD5 e0dc10df5f3bd26eb5edb1c1930cd283
BLAKE2b-256 a7d421d051a09c8b4dc5bd80ac5070e542c5b350f750b0cf99b94387952cc78f

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp38-cp38-win_amd64.whl.

File metadata

  • Download URL: small_gicp-0.1.3-cp38-cp38-win_amd64.whl
  • Upload date:
  • Size: 220.2 kB
  • Tags: CPython 3.8, Windows x86-64
  • Uploaded using Trusted Publishing? Yes
  • Uploaded via: twine/5.1.0 CPython/3.12.4

File hashes

Hashes for small_gicp-0.1.3-cp38-cp38-win_amd64.whl
Algorithm Hash digest
SHA256 af92f68f2afef0d5d540eb0191767e033dcff77d0cfbcc718a3c32dcf4c1b590
MD5 0b735f48458f7429c01a075a39ee1ec9
BLAKE2b-256 a2ffb1821ec6504e59fc4cce5568a15638c2755eb5cd1c6b54c095a42a36edee

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp38-cp38-manylinux_2_28_x86_64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp38-cp38-manylinux_2_28_x86_64.whl
Algorithm Hash digest
SHA256 3883cf01b1a9674eaf9c19f1ae3dd27f42498e84313052c37e5aeacbccef5977
MD5 8797738fcd5128079589b79c2c514555
BLAKE2b-256 cf097f6b1200047a033f075e4607662eaed6daef27a15fd1ce5322b6f682d800

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp38-cp38-manylinux_2_28_aarch64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp38-cp38-manylinux_2_28_aarch64.whl
Algorithm Hash digest
SHA256 4ab90b400ef81ba645a7d6429cc3f8636ad385fccc31dc13dd6120f5ab1bd2a0
MD5 14209d18cd3c26f5535410d61fd068f4
BLAKE2b-256 99796e2e036c6c55026b261fe5e09dbf663d25ff0172310d65ad9553f334113d

See more details on using hashes here.

File details

Details for the file small_gicp-0.1.3-cp38-cp38-macosx_11_0_arm64.whl.

File metadata

File hashes

Hashes for small_gicp-0.1.3-cp38-cp38-macosx_11_0_arm64.whl
Algorithm Hash digest
SHA256 ea37594be06a1388665c5929cccd99c915b0fdea29abc6d263177acf9b06c54b
MD5 5fa6c34679815174b4c8b8fb0eee507a
BLAKE2b-256 b94836c385e20f8fe196cc72118433778c7a8d387bb461a0f568281d6e1d0fdf

See more details on using hashes here.

Supported by

AWS AWS Cloud computing and Security Sponsor Datadog Datadog Monitoring Fastly Fastly CDN Google Google Download Analytics Microsoft Microsoft PSF Sponsor Pingdom Pingdom Monitoring Sentry Sentry Error logging StatusPage StatusPage Status page