mirror of https://github.com/koide3/small_gicp.git
fix: add max_iterations param of align in pybind interface (#52)
This commit is contained in:
parent
602d03762b
commit
5c6f13cfc9
|
|
@ -39,6 +39,7 @@ struct RegistrationSetting {
|
|||
double rotation_eps = 0.1 * M_PI / 180.0; ///< Rotation tolerance for convergence check [rad]
|
||||
double translation_eps = 1e-3; ///< Translation tolerance for convergence check
|
||||
int num_threads = 4; ///< Number of threads
|
||||
int max_iterations = 20; ///< Maximum number of iterations
|
||||
};
|
||||
|
||||
/// @brief Align point clouds
|
||||
|
|
|
|||
|
|
@ -31,7 +31,8 @@ void define_align(py::module& m) {
|
|||
double voxel_resolution,
|
||||
double downsampling_resolution,
|
||||
double max_correspondence_distance,
|
||||
int num_threads) {
|
||||
int num_threads,
|
||||
int max_iterations) {
|
||||
if (target_points.cols() != 3 && target_points.cols() != 4) {
|
||||
std::cerr << "target_points must be Nx3 or Nx4" << std::endl;
|
||||
return RegistrationResult(Eigen::Isometry3d::Identity());
|
||||
|
|
@ -92,6 +93,7 @@ void define_align(py::module& m) {
|
|||
py::arg("downsampling_resolution") = 0.25,
|
||||
py::arg("max_correspondence_distance") = 1.0,
|
||||
py::arg("num_threads") = 1,
|
||||
py::arg("max_iterations") = 20,
|
||||
R"pbdoc(
|
||||
Align two point clouds using various ICP-like algorithms.
|
||||
|
||||
|
|
@ -113,7 +115,8 @@ void define_align(py::module& m) {
|
|||
Maximum distance for matching points between point clouds.
|
||||
num_threads : int = 1
|
||||
Number of threads to use for parallel processing.
|
||||
|
||||
max_iterations : int = 20
|
||||
Maximum number of iterations for the optimization algorithm.
|
||||
Returns
|
||||
-------
|
||||
RegistrationResult
|
||||
|
|
@ -130,7 +133,8 @@ void define_align(py::module& m) {
|
|||
const Eigen::Matrix4d& init_T_target_source,
|
||||
const std::string& registration_type,
|
||||
double max_correspondence_distance,
|
||||
int num_threads) {
|
||||
int num_threads,
|
||||
int max_iterations) {
|
||||
RegistrationSetting setting;
|
||||
if (registration_type == "ICP") {
|
||||
setting.type = RegistrationSetting::ICP;
|
||||
|
|
@ -157,6 +161,7 @@ void define_align(py::module& m) {
|
|||
py::arg("registration_type") = "GICP",
|
||||
py::arg("max_correspondence_distance") = 1.0,
|
||||
py::arg("num_threads") = 1,
|
||||
py::arg("max_iterations") = 20,
|
||||
R"pbdoc(
|
||||
Align two point clouds using specified ICP-like algorithms, utilizing point cloud and KD-tree inputs.
|
||||
|
||||
|
|
@ -176,7 +181,8 @@ void define_align(py::module& m) {
|
|||
Maximum distance for corresponding point pairs.
|
||||
num_threads : int = 1
|
||||
Number of threads to use for computation.
|
||||
|
||||
max_iterations : int = 20
|
||||
Maximum number of iterations for the optimization algorithm.
|
||||
Returns
|
||||
-------
|
||||
RegistrationResult
|
||||
|
|
|
|||
|
|
@ -90,6 +90,7 @@ align(const PointCloud& target, const PointCloud& source, const KdTree<PointClou
|
|||
registration.rejector.max_dist_sq = setting.max_correspondence_distance * setting.max_correspondence_distance;
|
||||
registration.criteria.rotation_eps = setting.rotation_eps;
|
||||
registration.criteria.translation_eps = setting.translation_eps;
|
||||
registration.optimizer.max_iterations = setting.max_iterations;
|
||||
return registration.align(target, source, target_tree, init_T);
|
||||
}
|
||||
case RegistrationSetting::PLANE_ICP: {
|
||||
|
|
@ -98,6 +99,7 @@ align(const PointCloud& target, const PointCloud& source, const KdTree<PointClou
|
|||
registration.rejector.max_dist_sq = setting.max_correspondence_distance * setting.max_correspondence_distance;
|
||||
registration.criteria.rotation_eps = setting.rotation_eps;
|
||||
registration.criteria.translation_eps = setting.translation_eps;
|
||||
registration.optimizer.max_iterations = setting.max_iterations;
|
||||
return registration.align(target, source, target_tree, init_T);
|
||||
}
|
||||
case RegistrationSetting::GICP: {
|
||||
|
|
@ -106,6 +108,7 @@ align(const PointCloud& target, const PointCloud& source, const KdTree<PointClou
|
|||
registration.rejector.max_dist_sq = setting.max_correspondence_distance * setting.max_correspondence_distance;
|
||||
registration.criteria.rotation_eps = setting.rotation_eps;
|
||||
registration.criteria.translation_eps = setting.translation_eps;
|
||||
registration.optimizer.max_iterations = setting.max_iterations;
|
||||
return registration.align(target, source, target_tree, init_T);
|
||||
}
|
||||
case RegistrationSetting::VGICP: {
|
||||
|
|
@ -125,6 +128,7 @@ RegistrationResult align(const GaussianVoxelMap& target, const PointCloud& sourc
|
|||
registration.reduction.num_threads = setting.num_threads;
|
||||
registration.criteria.rotation_eps = setting.rotation_eps;
|
||||
registration.criteria.translation_eps = setting.translation_eps;
|
||||
registration.optimizer.max_iterations = setting.max_iterations;
|
||||
return registration.align(target, source, target, init_T);
|
||||
}
|
||||
|
||||
|
|
|
|||
Loading…
Reference in New Issue