Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix: add max_iterations param of align in pybind interface #52

Merged
merged 1 commit into from
May 18, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions include/small_gicp/registration/registration_helper.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
14 changes: 10 additions & 4 deletions src/python/align.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down Expand Up @@ -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.

Expand All @@ -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
Expand All @@ -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;
Expand All @@ -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.

Expand All @@ -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
Expand Down
4 changes: 4 additions & 0 deletions src/small_gicp/registration/registration_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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: {
Expand All @@ -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: {
Expand All @@ -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: {
Expand All @@ -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);
}

Expand Down
Loading