20 typename GeneralFactor = NullFactor,
21 typename CorrespondenceRejector = DistanceRejector,
22 typename Optimizer = LevenbergMarquardtOptimizer>
31 template <
typename TargetPo
intCloud,
typename SourcePo
intCloud,
typename TargetTree>
33 align(
const TargetPointCloud& target,
const SourcePointCloud& source,
const TargetTree& target_tree,
const Eigen::Isometry3d& init_T = Eigen::Isometry3d::Identity())
const {
35 std::cerr <<
"warning: target point cloud is too small. |target|=" <<
traits::size(target) << std::endl;
38 std::cerr <<
"warning: source point cloud is too small. |source|=" <<
traits::size(source) << std::endl;
size_t size(const T &points)
Get the number of points.
Definition: traits.hpp:16
Definition: flat_container.hpp:12
Registration result.
Definition: registration_result.hpp:11
Point cloud registration.
Definition: registration.hpp:23
GeneralFactor general_factor
General factor.
Definition: registration.hpp:51
typename PointFactor::Setting PointFactorSetting
Definition: registration.hpp:46
PointFactorSetting point_factor
Factor setting.
Definition: registration.hpp:50
RegistrationResult align(const TargetPointCloud &target, const SourcePointCloud &source, const TargetTree &target_tree, const Eigen::Isometry3d &init_T=Eigen::Isometry3d::Identity()) const
Align point clouds.
Definition: registration.hpp:33
TerminationCriteria criteria
Termination criteria.
Definition: registration.hpp:48
CorrespondenceRejector rejector
Correspondence rejector.
Definition: registration.hpp:49
Reduction reduction
Reduction.
Definition: registration.hpp:52
Optimizer optimizer
Optimizer.
Definition: registration.hpp:53
Registration termination criteria.
Definition: termination_criteria.hpp:10