Point cloud registration.
More...
#include <registration.hpp>
|
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...
|
|
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.
◆ PointFactorSetting
template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
◆ 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
-
target | Target point cloud |
source | Source point cloud |
target_tree | Nearest neighbor search for the target point cloud |
init_T | Initial guess |
- Returns
- Registration result
◆ criteria
template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
◆ 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 |
◆ 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 |
◆ point_factor
template<typename PointFactor , typename Reduction , typename GeneralFactor = NullFactor, typename CorrespondenceRejector = DistanceRejector, typename Optimizer = LevenbergMarquardtOptimizer>
◆ 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 |
◆ 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 |
The documentation for this struct was generated from the following file:
- /home/runner/work/small_gicp/small_gicp/include/small_gicp/registration/registration.hpp