|
small_gicp
|
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... | |
| using small_gicp::FlatContainerCov = typedef FlatContainer<false, true> |
FlatContainer with covariances.
| using small_gicp::FlatContainerNormal = typedef FlatContainer<true, false> |
FlatContainer with normals.
| using small_gicp::FlatContainerNormalCov = typedef FlatContainer<true, true> |
FlatContainer with normals and covariances.
| using small_gicp::FlatContainerPoints = typedef FlatContainer<false, false> |
FlatContainer that stores only points.
| using small_gicp::GaussianVoxelMap = typedef IncrementalVoxelMap<GaussianVoxel> |
| using small_gicp::NodeIndexType = typedef std::uint32_t |
| 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.
| target | Target Gaussian voxelmap |
| source | Source point cloud |
| init_T | Initial guess of T_target_source |
| setting | Registration setting |
| 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.
| target | Target point cloud |
| source | Source point cloud |
| target_tree | Nearest neighbor search for the target point cloud |
| init_T | Initial guess of T_target_source |
| setting | Registration setting |
| 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.
| target | Target points |
| source | Source points |
| init_T | Initial guess of T_target_source |
| setting | Registration setting |
| GaussianVoxelMap::Ptr small_gicp::create_gaussian_voxelmap | ( | const PointCloud & | points, |
| double | voxel_resolution | ||
| ) |
Create an incremental Gaussian voxel map.
| points | Input points |
| voxel_resolution | Voxel resolution |
| void small_gicp::estimate_covariances | ( | PointCloud & | cloud, |
| int | num_neighbors = 20 |
||
| ) |
Estimate point covariances.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_covariances | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20 |
||
| ) |
Estimate point covariances.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_covariances_omp | ( | PointCloud & | cloud, |
| int | num_neighbors = 20, |
||
| int | num_threads = 4 |
||
| ) |
Estimate point covariances with OpenMP.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| num_threads | Number of threads |
| void small_gicp::estimate_covariances_omp | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20, |
||
| int | num_threads = 4 |
||
| ) |
Estimate point covariances with OpenMP.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| num_threads | Number of threads |
| void small_gicp::estimate_covariances_tbb | ( | PointCloud & | cloud, |
| int | num_neighbors = 20 |
||
| ) |
Estimate point covariances with TBB.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_covariances_tbb | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20 |
||
| ) |
Estimate point covariances with TBB.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_local_features | ( | PointCloud & | cloud, |
| const KdTree & | kdtree, | ||
| int | num_neighbors | ||
| ) |
| void small_gicp::estimate_local_features | ( | PointCloud & | cloud, |
| int | num_neighbors | ||
| ) |
| void small_gicp::estimate_local_features | ( | PointCloud & | cloud, |
| Tree & | kdtree, | ||
| int | num_neighbors, | ||
| size_t | point_index | ||
| ) |
| void small_gicp::estimate_local_features_omp | ( | PointCloud & | cloud, |
| int | num_neighbors, | ||
| int | num_threads | ||
| ) |
| void small_gicp::estimate_local_features_omp | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors, | ||
| int | num_threads | ||
| ) |
| void small_gicp::estimate_local_features_tbb | ( | PointCloud & | cloud, |
| int | num_neighbors | ||
| ) |
| void small_gicp::estimate_local_features_tbb | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors | ||
| ) |
| void small_gicp::estimate_normals | ( | PointCloud & | cloud, |
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals_covariances | ( | PointCloud & | cloud, |
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals and covariances.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals_covariances | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals and covariances.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals_covariances_omp | ( | PointCloud & | cloud, |
| int | num_neighbors = 20, |
||
| int | num_threads = 4 |
||
| ) |
Estimate point normals and covariances with OpenMP.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| num_threads | Number of threads |
| 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.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| num_threads | Number of threads |
| void small_gicp::estimate_normals_covariances_tbb | ( | PointCloud & | cloud, |
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals and covariances with TBB.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals_covariances_tbb | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals and covariances with TBB.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals_omp | ( | PointCloud & | cloud, |
| int | num_neighbors = 20, |
||
| int | num_threads = 4 |
||
| ) |
Estimate point normals with OpenMP.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| num_threads | Number of threads |
| void small_gicp::estimate_normals_omp | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20, |
||
| int | num_threads = 4 |
||
| ) |
Estimate point normals with OpenMP.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
| num_threads | Number of threads |
| void small_gicp::estimate_normals_tbb | ( | PointCloud & | cloud, |
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals with TBB.
| cloud | [in/out] Point cloud |
| num_neighbors | Number of neighbors used for attribute estimation |
| void small_gicp::estimate_normals_tbb | ( | PointCloud & | cloud, |
| KdTree & | kdtree, | ||
| int | num_neighbors = 20 |
||
| ) |
Estimate point normals with TBB.
| cloud | [in/out] Point cloud |
| kdtree | Nearest neighbor search |
| num_neighbors | Number of neighbors used for attribute estimation |
|
inline |
Fast floor (https://stackoverflow.com/questions/824118/why-is-floor-so-slow).
| pt | Double vector |
| void small_gicp::merge_sort_omp | ( | RandomAccessIterator | first, |
| RandomAccessIterator | last, | ||
| const Compare & | comp, | ||
| int | num_threads | ||
| ) |
Merge sort with OpenMP parallelism.
| first | First iterator |
| last | Last iterator |
| comp | Comparison function |
| num_threads | Number of threads |
| 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.
| first | First iterator |
| last | Last iterator |
| comp | Comparison function |
|
inline |
| 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).
| points | Input points |
| downsampling_resolution | Downsample resolution |
| num_neighbors | Number of neighbors for normal/covariance estimation |
| num_threads | Number of threads |
| 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)
| void small_gicp::quick_sort_omp | ( | RandomAccessIterator | first, |
| RandomAccessIterator | last, | ||
| const Compare & | comp, | ||
| int | num_threads | ||
| ) |
Quick sort with OpenMP parallelism.
| first | First iterator |
| last | Last iterator |
| comp | Comparison function |
| num_threads | Number of threads |
| 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.
| first | First iterator |
| last | Last iterator |
| comp | Comparison function |
| void small_gicp::radix_sort_tbb | ( | T * | first_, |
| T * | last_, | ||
| const KeyFunc & | key_ | ||
| ) |
Radix sort with TBB parallelization.
| T | Data type (must be unsigned integral type) |
| KeyFunc | Key function |
| bits | Number of bits per step |
| tile_size | Tile size |
| first_ | [in/out] First iterator |
| last_ | [in/out] Last iterator |
| key_ | Key function (T => uint) |
| void small_gicp::radix_sort_tbb | ( | T * | first_, |
| T * | last_, | ||
| const KeyFunc & | key_, | ||
| RadixSortBuffers< T > & | buffers | ||
| ) |
Radix sort with TBB parallelization.
| T | Data type (must be unsigned integral type) |
| KeyFunc | Key function |
| bits | Number of bits per step |
| tile_size | Tile size |
| first_ | [in/out] First iterator |
| last_ | [in/out] Last iterator |
| key_ | Key function (T => uint) |
| buffers | Temporal buffers |
| std::shared_ptr<OutputPointCloud> small_gicp::random_sampling | ( | const InputPointCloud & | points, |
| size_t | num_samples, | ||
| RNG & | rng | ||
| ) |
Random downsampling.
| points | Input points |
| num_samples | Number of samples to be drawn |
|
inline |
SE3 expmap (Rotation-first).
| a | Twist vector [rx, ry, rz, tx, ty, tz] |
Note: That is an accurate expansion!
|
inline |
Create skew symmetric matrix.
| x | Rotation vector |
|
inline |
SO3 expmap.
| omega | [rx, ry, rz] |
| 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.
| points | Input points |
| leaf_size | Downsampling resolution |
| 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.
| points | Input points |
| leaf_size | Downsampling resolution |
| std::shared_ptr<OutputPointCloud> small_gicp::voxelgrid_sampling_tbb | ( | const InputPointCloud & | points, |
| double | leaf_size | ||
| ) |
Voxel grid downsampling with TBB backend.
| points | Input points |
| leaf_size | Downsampling resolution |