small_gicp
Namespaces | Classes | Typedefs | Functions
small_gicp Namespace Reference

Namespaces

 traits
 

Classes

struct  FlatContainer
 Point container with a flat vector. More...
 
struct  GaussianVoxel
 Gaussian voxel that computes and stores voxel mean and covariance. More...
 
struct  VoxelInfo
 Voxel meta information. More...
 
struct  IncrementalVoxelMap
 Incremental voxelmap. This class supports incremental point cloud insertion and LRU-based voxel deletion that removes voxels that are not recently referenced. More...
 
struct  KdTreeNode
 KdTree node. More...
 
struct  KdTreeBuilder
 Single thread Kd-tree builder. More...
 
struct  UnsafeKdTree
 "Unsafe" KdTree. More...
 
struct  KdTree
 "Safe" KdTree that holds the ownership of the input points. More...
 
struct  KdTreeBuilderOMP
 Kd-tree builder with OpenMP. More...
 
struct  KdTreeBuilderTBB
 Kd-tree builder with TBB. More...
 
struct  KnnSetting
 K-nearest neighbor search setting. More...
 
struct  identity_transform
 Identity transform (alternative to std::identity in C++20). More...
 
struct  KnnResult
 K-nearest neighbor search result container. More...
 
struct  ProjectionSetting
 Parameters to control the projection axis search. More...
 
struct  AxisAlignedProjection
 Conventional axis-aligned projection (i.e., selecting any of XYZ axes with the largest variance). More...
 
struct  NormalProjection
 Normal projection (i.e., selecting the 3D direction with the largest variance of the points). More...
 
struct  NullFactor
 Null factor that gives no constraints. More...
 
struct  RestrictDoFFactor
 Factor to restrict the degrees of freedom of optimization (e.g., fixing roll, pitch rotation). More...
 
struct  GICPFactor
 GICP (distribution-to-distribution) per-point error factor. More...
 
struct  ICPFactor
 Point-to-point per-point error factor. More...
 
struct  PointToPlaneICPFactor
 Point-to-plane per-point error factor. More...
 
struct  Huber
 Huber robust kernel. More...
 
struct  Cauchy
 Cauchy robust kernel. More...
 
struct  RobustFactor
 Robustify a factor with a robust kernel. More...
 
struct  PointCloudProxy
 Proxy class to access PCL point cloud with external covariance matrices. More...
 
class  RegistrationPCL
 PCL registration interfaces. More...
 
struct  PointCloud
 Point cloud. More...
 
struct  GaussNewtonOptimizer
 GaussNewton optimizer. More...
 
struct  LevenbergMarquardtOptimizer
 LevenbergMarquardt optimizer. More...
 
struct  SerialReduction
 Single-thread reduction. More...
 
struct  ParallelReductionOMP
 Parallel reduction with OpenMP backend. More...
 
struct  LinearizeSum
 Summation for linearized systems. More...
 
struct  ErrorSum
 Summation for evaluated errors. More...
 
struct  ParallelReductionTBB
 Parallel reduction with TBB backend. More...
 
struct  Registration
 Point cloud registration. More...
 
struct  RegistrationSetting
 Registration setting. More...
 
struct  RegistrationResult
 Registration result. More...
 
struct  NullRejector
 Null correspondence rejector. This class accepts all input correspondences. More...
 
struct  DistanceRejector
 Rejecting correspondences with large distances. More...
 
struct  TerminationCriteria
 Registration termination criteria. More...
 
struct  NormalSetter
 Computes point normals from eigenvectors and sets them to the point cloud. More...
 
struct  CovarianceSetter
 Computes point covariances from eigenvectors and sets them to the point cloud. More...
 
struct  NormalCovarianceSetter
 Computes point normals and covariances from eigenvectors and sets them to the point cloud. More...
 
struct  RadixSortBuffers
 Temporal buffers for radix sort. More...
 
struct  XORVector3iHash
 Spatial hashing function. Teschner et al., "Optimized Spatial Hashing for Collision Detection of Deformable Objects", VMV2003. More...
 

Typedefs

using FlatContainerPoints = FlatContainer< false, false >
 FlatContainer that stores only points. More...
 
using FlatContainerNormal = FlatContainer< true, false >
 FlatContainer with normals. More...
 
using FlatContainerCov = FlatContainer< false, true >
 FlatContainer with covariances. More...
 
using FlatContainerNormalCov = FlatContainer< true, true >
 FlatContainer with normals and covariances. More...
 
using GaussianVoxelMap = IncrementalVoxelMap< GaussianVoxel >
 
using NodeIndexType = std::uint32_t
 

Functions

int omp_get_thread_num ()
 
std::pair< PointCloud::Ptr, std::shared_ptr< KdTree< PointCloud > > > preprocess_points (const PointCloud &points, double downsampling_resolution, int num_neighbors=10, int num_threads=4)
 Preprocess point cloud (downsampling, kdtree creation, and normal and covariance estimation). More...
 
template<typename T , int D>
std::pair< PointCloud::Ptr, std::shared_ptr< KdTree< PointCloud > > > preprocess_points (const std::vector< Eigen::Matrix< T, D, 1 >> &points, double downsampling_resolution, int num_neighbors=10, int num_threads=4)
 Preprocess point cloud (downsampling, kdtree creation, and normal and covariance estimation) More...
 
GaussianVoxelMap::Ptr create_gaussian_voxelmap (const PointCloud &points, double voxel_resolution)
 Create an incremental Gaussian voxel map. More...
 
template<typename T , int D>
RegistrationResult align (const std::vector< Eigen::Matrix< T, D, 1 >> &target, const std::vector< Eigen::Matrix< T, D, 1 >> &source, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity(), const RegistrationSetting &setting=RegistrationSetting())
 Align point clouds. More...
 
RegistrationResult align (const PointCloud &target, const PointCloud &source, const KdTree< PointCloud > &target_tree, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity(), const RegistrationSetting &setting=RegistrationSetting())
 Align preprocessed point clouds. More...
 
RegistrationResult align (const GaussianVoxelMap &target, const PointCloud &source, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity(), const RegistrationSetting &setting=RegistrationSetting())
 Align preprocessed point clouds with VGICP. More...
 
template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud>
std::shared_ptr< OutputPointCloud > voxelgrid_sampling (const InputPointCloud &points, double leaf_size)
 Voxelgrid downsampling. This function computes exact average of points in each voxel, and each voxel can contain arbitrary number of points. More...
 
template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud, typename RNG = std::mt19937>
std::shared_ptr< OutputPointCloud > random_sampling (const InputPointCloud &points, size_t num_samples, RNG &rng)
 Random downsampling. More...
 
template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud>
std::shared_ptr< OutputPointCloud > voxelgrid_sampling_omp (const InputPointCloud &points, double leaf_size, int num_threads=4)
 Voxel grid downsampling with OpenMP backend. More...
 
template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud>
std::shared_ptr< OutputPointCloud > voxelgrid_sampling_tbb (const InputPointCloud &points, double leaf_size)
 Voxel grid downsampling with TBB backend. More...
 
Eigen::Array4i fast_floor (const Eigen::Array4d &pt)
 Fast floor (https://stackoverflow.com/questions/824118/why-is-floor-so-slow). More...
 
Eigen::Matrix3d skew (const Eigen::Vector3d &x)
 Create skew symmetric matrix. More...
 
Eigen::Quaterniond so3_exp (const Eigen::Vector3d &omega)
 SO3 expmap. More...
 
Eigen::Isometry3d se3_exp (const Eigen::Matrix< double, 6, 1 > &a)
 SE3 expmap (Rotation-first). More...
 
template<typename Setter , typename PointCloud , typename Tree >
void estimate_local_features (PointCloud &cloud, Tree &kdtree, int num_neighbors, size_t point_index)
 
template<typename Setter , typename PointCloud , typename KdTree >
void estimate_local_features (PointCloud &cloud, const KdTree &kdtree, int num_neighbors)
 
template<typename Setter , typename PointCloud >
void estimate_local_features (PointCloud &cloud, int num_neighbors)
 
template<typename PointCloud >
void estimate_normals (PointCloud &cloud, int num_neighbors=20)
 Estimate point normals. More...
 
template<typename PointCloud , typename KdTree >
void estimate_normals (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20)
 Estimate point normals. More...
 
template<typename PointCloud >
void estimate_covariances (PointCloud &cloud, int num_neighbors=20)
 Estimate point covariances. More...
 
template<typename PointCloud , typename KdTree >
void estimate_covariances (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20)
 Estimate point covariances. More...
 
template<typename PointCloud >
void estimate_normals_covariances (PointCloud &cloud, int num_neighbors=20)
 Estimate point normals and covariances. More...
 
template<typename PointCloud , typename KdTree >
void estimate_normals_covariances (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20)
 Estimate point normals and covariances. More...
 
template<typename Setter , typename PointCloud >
void estimate_local_features_omp (PointCloud &cloud, int num_neighbors, int num_threads)
 
template<typename Setter , typename PointCloud , typename KdTree >
void estimate_local_features_omp (PointCloud &cloud, KdTree &kdtree, int num_neighbors, int num_threads)
 
template<typename PointCloud >
void estimate_normals_omp (PointCloud &cloud, int num_neighbors=20, int num_threads=4)
 Estimate point normals with OpenMP. More...
 
template<typename PointCloud , typename KdTree >
void estimate_normals_omp (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20, int num_threads=4)
 Estimate point normals with OpenMP. More...
 
template<typename PointCloud >
void estimate_covariances_omp (PointCloud &cloud, int num_neighbors=20, int num_threads=4)
 Estimate point covariances with OpenMP. More...
 
template<typename PointCloud , typename KdTree >
void estimate_covariances_omp (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20, int num_threads=4)
 Estimate point covariances with OpenMP. More...
 
template<typename PointCloud >
void estimate_normals_covariances_omp (PointCloud &cloud, int num_neighbors=20, int num_threads=4)
 Estimate point normals and covariances with OpenMP. More...
 
template<typename PointCloud , typename KdTree >
void estimate_normals_covariances_omp (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20, int num_threads=4)
 Estimate point normals and covariances with OpenMP. More...
 
template<typename Setter , typename PointCloud , typename KdTree >
void estimate_local_features_tbb (PointCloud &cloud, KdTree &kdtree, int num_neighbors)
 
template<typename Setter , typename PointCloud >
void estimate_local_features_tbb (PointCloud &cloud, int num_neighbors)
 
template<typename PointCloud >
void estimate_normals_tbb (PointCloud &cloud, int num_neighbors=20)
 Estimate point normals with TBB. More...
 
template<typename PointCloud , typename KdTree >
void estimate_normals_tbb (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20)
 Estimate point normals with TBB. More...
 
template<typename PointCloud >
void estimate_covariances_tbb (PointCloud &cloud, int num_neighbors=20)
 Estimate point covariances with TBB. More...
 
template<typename PointCloud , typename KdTree >
void estimate_covariances_tbb (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20)
 Estimate point covariances with TBB. More...
 
template<typename PointCloud >
void estimate_normals_covariances_tbb (PointCloud &cloud, int num_neighbors=20)
 Estimate point normals and covariances with TBB. More...
 
template<typename PointCloud , typename KdTree >
void estimate_normals_covariances_tbb (PointCloud &cloud, KdTree &kdtree, int num_neighbors=20)
 Estimate point normals and covariances with TBB. More...
 
template<typename RandomAccessIterator , typename Compare >
void merge_sort_omp_impl (RandomAccessIterator first, RandomAccessIterator last, const Compare &comp)
 Implementation of merge sort with OpenMP parallelism. Do not call this directly. Use merge_sort_omp instead. More...
 
template<typename RandomAccessIterator , typename Compare >
void merge_sort_omp (RandomAccessIterator first, RandomAccessIterator last, const Compare &comp, int num_threads)
 Merge sort with OpenMP parallelism. More...
 
template<typename RandomAccessIterator , typename Compare >
void quick_sort_omp_impl (RandomAccessIterator first, RandomAccessIterator last, const Compare &comp)
 Implementation of quick sort with OpenMP parallelism. Do not call this directly. Use quick_sort_omp instead. More...
 
template<typename RandomAccessIterator , typename Compare >
void quick_sort_omp (RandomAccessIterator first, RandomAccessIterator last, const Compare &comp, int num_threads)
 Quick sort with OpenMP parallelism. More...
 
template<typename T , typename KeyFunc , int bits = 8, int tile_size = 256>
void radix_sort_tbb (T *first_, T *last_, const KeyFunc &key_, RadixSortBuffers< T > &buffers)
 Radix sort with TBB parallelization. More...
 
template<typename T , typename KeyFunc , int bits = 4, int tile_size = 256>
void radix_sort_tbb (T *first_, T *last_, const KeyFunc &key_)
 Radix sort with TBB parallelization. More...
 

Typedef Documentation

◆ FlatContainerCov

using small_gicp::FlatContainerCov = typedef FlatContainer<false, true>

FlatContainer with covariances.

◆ FlatContainerNormal

using small_gicp::FlatContainerNormal = typedef FlatContainer<true, false>

FlatContainer with normals.

◆ FlatContainerNormalCov

FlatContainer with normals and covariances.

◆ FlatContainerPoints

using small_gicp::FlatContainerPoints = typedef FlatContainer<false, false>

FlatContainer that stores only points.

◆ GaussianVoxelMap

◆ NodeIndexType

using small_gicp::NodeIndexType = typedef std::uint32_t

Function Documentation

◆ align() [1/3]

RegistrationResult small_gicp::align ( const GaussianVoxelMap target,
const PointCloud source,
const Eigen::Isometry3d &  init_T = Eigen::Isometry3d::Identity(),
const RegistrationSetting setting = RegistrationSetting() 
)

Align preprocessed point clouds with VGICP.

Parameters
targetTarget Gaussian voxelmap
sourceSource point cloud
init_TInitial guess of T_target_source
settingRegistration setting
Returns
Registration result

◆ align() [2/3]

RegistrationResult small_gicp::align ( const PointCloud target,
const PointCloud source,
const KdTree< PointCloud > &  target_tree,
const Eigen::Isometry3d &  init_T = Eigen::Isometry3d::Identity(),
const RegistrationSetting setting = RegistrationSetting() 
)

Align preprocessed point clouds.

Parameters
targetTarget point cloud
sourceSource point cloud
target_treeNearest neighbor search for the target point cloud
init_TInitial guess of T_target_source
settingRegistration setting
Returns
Registration result

◆ align() [3/3]

template<typename T , int D>
RegistrationResult small_gicp::align ( const std::vector< Eigen::Matrix< T, D, 1 >> &  target,
const std::vector< Eigen::Matrix< T, D, 1 >> &  source,
const Eigen::Isometry3d &  init_T = Eigen::Isometry3d::Identity(),
const RegistrationSetting setting = RegistrationSetting() 
)

Align point clouds.

Note
This function only accepts Eigen::Vector(3|4)(f|d) as input
See also
small_gicp::voxelgrid_sampling_omp, small_gicp::estimate_normals_covariances_omp
Parameters
targetTarget points
sourceSource points
init_TInitial guess of T_target_source
settingRegistration setting
Returns
Registration result

◆ create_gaussian_voxelmap()

GaussianVoxelMap::Ptr small_gicp::create_gaussian_voxelmap ( const PointCloud points,
double  voxel_resolution 
)

Create an incremental Gaussian voxel map.

See also
small_gicp::IncrementalVoxelMap
Parameters
pointsInput points
voxel_resolutionVoxel resolution

◆ estimate_covariances() [1/2]

template<typename PointCloud >
void small_gicp::estimate_covariances ( PointCloud cloud,
int  num_neighbors = 20 
)

Estimate point covariances.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_covariances() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_covariances ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20 
)

Estimate point covariances.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_covariances_omp() [1/2]

template<typename PointCloud >
void small_gicp::estimate_covariances_omp ( PointCloud cloud,
int  num_neighbors = 20,
int  num_threads = 4 
)

Estimate point covariances with OpenMP.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation
num_threadsNumber of threads

◆ estimate_covariances_omp() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_covariances_omp ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20,
int  num_threads = 4 
)

Estimate point covariances with OpenMP.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation
num_threadsNumber of threads

◆ estimate_covariances_tbb() [1/2]

template<typename PointCloud >
void small_gicp::estimate_covariances_tbb ( PointCloud cloud,
int  num_neighbors = 20 
)

Estimate point covariances with TBB.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_covariances_tbb() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_covariances_tbb ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20 
)

Estimate point covariances with TBB.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_local_features() [1/3]

template<typename Setter , typename PointCloud , typename KdTree >
void small_gicp::estimate_local_features ( PointCloud cloud,
const KdTree kdtree,
int  num_neighbors 
)

◆ estimate_local_features() [2/3]

template<typename Setter , typename PointCloud >
void small_gicp::estimate_local_features ( PointCloud cloud,
int  num_neighbors 
)

◆ estimate_local_features() [3/3]

template<typename Setter , typename PointCloud , typename Tree >
void small_gicp::estimate_local_features ( PointCloud cloud,
Tree &  kdtree,
int  num_neighbors,
size_t  point_index 
)

◆ estimate_local_features_omp() [1/2]

template<typename Setter , typename PointCloud >
void small_gicp::estimate_local_features_omp ( PointCloud cloud,
int  num_neighbors,
int  num_threads 
)

◆ estimate_local_features_omp() [2/2]

template<typename Setter , typename PointCloud , typename KdTree >
void small_gicp::estimate_local_features_omp ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors,
int  num_threads 
)

◆ estimate_local_features_tbb() [1/2]

template<typename Setter , typename PointCloud >
void small_gicp::estimate_local_features_tbb ( PointCloud cloud,
int  num_neighbors 
)

◆ estimate_local_features_tbb() [2/2]

template<typename Setter , typename PointCloud , typename KdTree >
void small_gicp::estimate_local_features_tbb ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors 
)

◆ estimate_normals() [1/2]

template<typename PointCloud >
void small_gicp::estimate_normals ( PointCloud cloud,
int  num_neighbors = 20 
)

Estimate point normals.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_normals ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20 
)

Estimate point normals.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals_covariances() [1/2]

template<typename PointCloud >
void small_gicp::estimate_normals_covariances ( PointCloud cloud,
int  num_neighbors = 20 
)

Estimate point normals and covariances.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals_covariances() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_normals_covariances ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20 
)

Estimate point normals and covariances.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals_covariances_omp() [1/2]

template<typename PointCloud >
void small_gicp::estimate_normals_covariances_omp ( PointCloud cloud,
int  num_neighbors = 20,
int  num_threads = 4 
)

Estimate point normals and covariances with OpenMP.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation
num_threadsNumber of threads

◆ estimate_normals_covariances_omp() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_normals_covariances_omp ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20,
int  num_threads = 4 
)

Estimate point normals and covariances with OpenMP.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation
num_threadsNumber of threads

◆ estimate_normals_covariances_tbb() [1/2]

template<typename PointCloud >
void small_gicp::estimate_normals_covariances_tbb ( PointCloud cloud,
int  num_neighbors = 20 
)

Estimate point normals and covariances with TBB.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals_covariances_tbb() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_normals_covariances_tbb ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20 
)

Estimate point normals and covariances with TBB.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals_omp() [1/2]

template<typename PointCloud >
void small_gicp::estimate_normals_omp ( PointCloud cloud,
int  num_neighbors = 20,
int  num_threads = 4 
)

Estimate point normals with OpenMP.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation
num_threadsNumber of threads

◆ estimate_normals_omp() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_normals_omp ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20,
int  num_threads = 4 
)

Estimate point normals with OpenMP.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation
num_threadsNumber of threads

◆ estimate_normals_tbb() [1/2]

template<typename PointCloud >
void small_gicp::estimate_normals_tbb ( PointCloud cloud,
int  num_neighbors = 20 
)

Estimate point normals with TBB.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
num_neighborsNumber of neighbors used for attribute estimation

◆ estimate_normals_tbb() [2/2]

template<typename PointCloud , typename KdTree >
void small_gicp::estimate_normals_tbb ( PointCloud cloud,
KdTree kdtree,
int  num_neighbors = 20 
)

Estimate point normals with TBB.

Note
If a sufficient number of neighbor points for normal/covariance estimation (5 points) is not found, an invalid normal/covariance is set to the point (normal=zero vector, covariance=identity matrix).
Parameters
cloud[in/out] Point cloud
kdtreeNearest neighbor search
num_neighborsNumber of neighbors used for attribute estimation

◆ fast_floor()

Eigen::Array4i small_gicp::fast_floor ( const Eigen::Array4d &  pt)
inline

Fast floor (https://stackoverflow.com/questions/824118/why-is-floor-so-slow).

Parameters
ptDouble vector
Returns
Floored int vector

◆ merge_sort_omp()

template<typename RandomAccessIterator , typename Compare >
void small_gicp::merge_sort_omp ( RandomAccessIterator  first,
RandomAccessIterator  last,
const Compare &  comp,
int  num_threads 
)

Merge sort with OpenMP parallelism.

Note
This tends to be slower than quick_sort_omp.
Parameters
firstFirst iterator
lastLast iterator
compComparison function
num_threadsNumber of threads

◆ merge_sort_omp_impl()

template<typename RandomAccessIterator , typename Compare >
void small_gicp::merge_sort_omp_impl ( RandomAccessIterator  first,
RandomAccessIterator  last,
const Compare &  comp 
)

Implementation of merge sort with OpenMP parallelism. Do not call this directly. Use merge_sort_omp instead.

Parameters
firstFirst iterator
lastLast iterator
compComparison function

◆ omp_get_thread_num()

int small_gicp::omp_get_thread_num ( )
inline

◆ preprocess_points() [1/2]

std::pair<PointCloud::Ptr, std::shared_ptr<KdTree<PointCloud> > > small_gicp::preprocess_points ( const PointCloud points,
double  downsampling_resolution,
int  num_neighbors = 10,
int  num_threads = 4 
)

Preprocess point cloud (downsampling, kdtree creation, and normal and covariance estimation).

Note
When num_threads >= 2, this function has minor run-by-run non-determinism due to the parallel downsampling.
See also
small_gicp::voxelgrid_sampling_omp, small_gicp::estimate_normals_covariances_omp
Parameters
pointsInput points
downsampling_resolutionDownsample resolution
num_neighborsNumber of neighbors for normal/covariance estimation
num_threadsNumber of threads

◆ preprocess_points() [2/2]

template<typename T , int D>
std::pair<PointCloud::Ptr, std::shared_ptr<KdTree<PointCloud> > > small_gicp::preprocess_points ( const std::vector< Eigen::Matrix< T, D, 1 >> &  points,
double  downsampling_resolution,
int  num_neighbors = 10,
int  num_threads = 4 
)

Preprocess point cloud (downsampling, kdtree creation, and normal and covariance estimation)

Note
This function only accepts Eigen::Vector(3|4)(f|d) as input
When num_threads >= 2, this function has minor run-by-run non-determinism due to the parallel downsampling.
See also
small_gicp::voxelgrid_sampling_omp, small_gicp::estimate_normals_covariances_omp

◆ quick_sort_omp()

template<typename RandomAccessIterator , typename Compare >
void small_gicp::quick_sort_omp ( RandomAccessIterator  first,
RandomAccessIterator  last,
const Compare &  comp,
int  num_threads 
)

Quick sort with OpenMP parallelism.

Parameters
firstFirst iterator
lastLast iterator
compComparison function
num_threadsNumber of threads

◆ quick_sort_omp_impl()

template<typename RandomAccessIterator , typename Compare >
void small_gicp::quick_sort_omp_impl ( RandomAccessIterator  first,
RandomAccessIterator  last,
const Compare &  comp 
)

Implementation of quick sort with OpenMP parallelism. Do not call this directly. Use quick_sort_omp instead.

Parameters
firstFirst iterator
lastLast iterator
compComparison function

◆ radix_sort_tbb() [1/2]

template<typename T , typename KeyFunc , int bits = 4, int tile_size = 256>
void small_gicp::radix_sort_tbb ( T *  first_,
T *  last_,
const KeyFunc &  key_ 
)

Radix sort with TBB parallelization.

Template Parameters
TData type (must be unsigned integral type)
KeyFuncKey function
bitsNumber of bits per step
tile_sizeTile size
Parameters
first_[in/out] First iterator
last_[in/out] Last iterator
key_Key function (T => uint)

◆ radix_sort_tbb() [2/2]

template<typename T , typename KeyFunc , int bits = 8, int tile_size = 256>
void small_gicp::radix_sort_tbb ( T *  first_,
T *  last_,
const KeyFunc &  key_,
RadixSortBuffers< T > &  buffers 
)

Radix sort with TBB parallelization.

Note
This function outperforms tbb::parallel_sort only in case with many elements and threads. For usual data size and number of threads, use tbb::parallel_sort.
Template Parameters
TData type (must be unsigned integral type)
KeyFuncKey function
bitsNumber of bits per step
tile_sizeTile size
Parameters
first_[in/out] First iterator
last_[in/out] Last iterator
key_Key function (T => uint)
buffersTemporal buffers

◆ random_sampling()

template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud, typename RNG = std::mt19937>
std::shared_ptr<OutputPointCloud> small_gicp::random_sampling ( const InputPointCloud &  points,
size_t  num_samples,
RNG &  rng 
)

Random downsampling.

Parameters
pointsInput points
num_samplesNumber of samples to be drawn
Returns
Downsampled points

◆ se3_exp()

Eigen::Isometry3d small_gicp::se3_exp ( const Eigen::Matrix< double, 6, 1 > &  a)
inline

SE3 expmap (Rotation-first).

Parameters
aTwist vector [rx, ry, rz, tx, ty, tz]
Returns
SE3 matrix

Note: That is an accurate expansion!

◆ skew()

Eigen::Matrix3d small_gicp::skew ( const Eigen::Vector3d &  x)
inline

Create skew symmetric matrix.

Parameters
xRotation vector
Returns
Skew symmetric matrix

◆ so3_exp()

Eigen::Quaterniond small_gicp::so3_exp ( const Eigen::Vector3d &  omega)
inline

SO3 expmap.

Parameters
omega[rx, ry, rz]
Returns
Quaternion

◆ voxelgrid_sampling()

template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud>
std::shared_ptr<OutputPointCloud> small_gicp::voxelgrid_sampling ( const InputPointCloud &  points,
double  leaf_size 
)

Voxelgrid downsampling. This function computes exact average of points in each voxel, and each voxel can contain arbitrary number of points.

Note
Discretized voxel coords must be in 21bit range [-1048576, 1048575]. For example, if the downsampling resolution is 0.01 m, point coordinates must be in [-10485.76, 10485.75] m. Points outside the valid range will be ignored.
Parameters
pointsInput points
leaf_sizeDownsampling resolution
Returns
Downsampled points

◆ voxelgrid_sampling_omp()

template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud>
std::shared_ptr<OutputPointCloud> small_gicp::voxelgrid_sampling_omp ( const InputPointCloud &  points,
double  leaf_size,
int  num_threads = 4 
)

Voxel grid downsampling with OpenMP backend.

Note
This function has minor run-by-run non-deterministic behavior due to parallel data collection that results in a deviation of the number of points in the downsampling results (up to 10% increase from the single-thread version).
Discretized voxel coords must be in 21bit range [-1048576, 1048575]. For example, if the downsampling resolution is 0.01 m, point coordinates must be in [-10485.76, 10485.75] m. Points outside the valid range will be ignored.
Parameters
pointsInput points
leaf_sizeDownsampling resolution
Returns
Downsampled points

◆ voxelgrid_sampling_tbb()

template<typename InputPointCloud , typename OutputPointCloud = InputPointCloud>
std::shared_ptr<OutputPointCloud> small_gicp::voxelgrid_sampling_tbb ( const InputPointCloud &  points,
double  leaf_size 
)

Voxel grid downsampling with TBB backend.

Note
This function has minor run-by-run non-deterministic behavior due to parallel data collection that results in a deviation of the number of points in the downsampling results (up to 10% increase from the single-thread version).
Discretized voxel coords must be in 21bit range [-1048576, 1048575]. For example, if the downsampling resolution is 0.01 m, point coordinates must be in [-10485.76, 10485.75] m. Points outside the valid range will be ignored.
Parameters
pointsInput points
leaf_sizeDownsampling resolution
Returns
Downsampled points