small_gicp
Public Types | Public Member Functions | Public Attributes | List of all members
small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer > Struct Template Reference

Point cloud registration. More...

#include <registration.hpp>

Collaboration diagram for small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >:
Collaboration graph
[legend]

Public Types

using PointFactorSetting = typename PointFactor::Setting
 

Public Member Functions

template<typename TargetPointCloud , typename SourcePointCloud , typename TargetTree >
RegistrationResult align (const TargetPointCloud &target, const SourcePointCloud &source, const TargetTree &target_tree, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity()) const
 Align point clouds. More...
 

Public Attributes

TerminationCriteria criteria
 Termination criteria. More...
 
CorrespondenceRejector rejector
 Correspondence rejector. More...
 
PointFactorSetting point_factor
 Factor setting. More...
 
GeneralFactor general_factor
 General factor. More...
 
Reduction reduction
 Reduction. More...
 
Optimizer optimizer
 Optimizer. More...
 

Detailed Description

template<typename PointFactor, typename Reduction, typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
struct small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >

Point cloud registration.

Member Typedef Documentation

◆ PointFactorSetting

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
using small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::PointFactorSetting = typename PointFactor::Setting

Member Function Documentation

◆ align()

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
template<typename TargetPointCloud , typename SourcePointCloud , typename TargetTree >
RegistrationResult small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::align ( const TargetPointCloud &  target,
const SourcePointCloud &  source,
const TargetTree &  target_tree,
const Eigen::Isometry3d &  init_T = Eigen::Isometry3d::Identity() 
) const
inline

Align point clouds.

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

Member Data Documentation

◆ criteria

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
TerminationCriteria small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::criteria

Termination criteria.

◆ general_factor

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
GeneralFactor small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::general_factor

General factor.

◆ optimizer

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
Optimizer small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::optimizer

Optimizer.

◆ point_factor

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
PointFactorSetting small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::point_factor

Factor setting.

◆ reduction

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
Reduction small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::reduction

Reduction.

◆ rejector

template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
CorrespondenceRejector small_gicp::Registration< PointFactor, Reduction, GeneralFactor, CorrespondenceRejector, Optimizer >::rejector

Correspondence rejector.


The documentation for this struct was generated from the following file: