Skip to content

Commit

Permalink
expose verbose option to python (#77)
Browse files Browse the repository at this point in the history
* expose verbose option to python

* tweak convergence check
  • Loading branch information
koide3 authored Jun 27, 2024
1 parent e95cb19 commit 45b0b29
Show file tree
Hide file tree
Showing 8 changed files with 31 additions and 13 deletions.
2 changes: 1 addition & 1 deletion include/small_gicp/ann/incremental_voxelmap.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ struct IncrementalVoxelMap {

/// @brief Calculate the global point index from the voxel index and the point index.
inline size_t calc_index(const size_t voxel_id, const size_t point_id) const { return (voxel_id << point_id_bits) | point_id; }
inline size_t voxel_id(const size_t i) const { return i >> point_id_bits; } ///< Extract the point ID from a global index.
inline size_t voxel_id(const size_t i) const { return i >> point_id_bits; } ///< Extract the point ID from a global index.
inline size_t point_id(const size_t i) const { return i & ((1ull << point_id_bits) - 1); } ///< Extract the voxel ID from a global index.

public:
Expand Down
2 changes: 1 addition & 1 deletion include/small_gicp/registration/optimizer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ struct LevenbergMarquardtOptimizer {
<< " dr=" << delta.head<3>().norm() << std::endl;
}

if (new_e < e) {
if (new_e <= e) {
// Error decreased, decrease lambda
result.converged = criteria.converged(delta);
result.T_target_source = new_T;
Expand Down
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 @@ -40,6 +40,7 @@ struct RegistrationSetting {
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
bool verbose = false; ///< Verbose mode
};

/// @brief Align point clouds
Expand Down
2 changes: 1 addition & 1 deletion include/small_gicp/registration/termination_criteria.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ struct TerminationCriteria {
/// @brief Check the convergence
/// @param delta Transformation update vector
/// @return True if converged
bool converged(const Eigen::Matrix<double, 6, 1>& delta) const { return delta.template head<3>().norm() < rotation_eps && delta.template tail<3>().norm() < translation_eps; }
bool converged(const Eigen::Matrix<double, 6, 1>& delta) const { return delta.template head<3>().norm() <= rotation_eps && delta.template tail<3>().norm() <= translation_eps; }

double translation_eps; ///< Rotation tolerance [rad]
double rotation_eps; ///< Translation tolerance
Expand Down
2 changes: 1 addition & 1 deletion include/small_gicp/util/downsampling.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ std::shared_ptr<OutputPointCloud> voxelgrid_sampling(const InputPointCloud& poin
}

// Compute voxel coord bits (0|1bit, z|21bit, y|21bit, x|21bit)
const std::uint64_t bits = //
const std::uint64_t bits = //
(static_cast<std::uint64_t>(coord[0] & coord_bit_mask) << (coord_bit_size * 0)) | //
(static_cast<std::uint64_t>(coord[1] & coord_bit_mask) << (coord_bit_size * 1)) | //
(static_cast<std::uint64_t>(coord[2] & coord_bit_mask) << (coord_bit_size * 2));
Expand Down
8 changes: 2 additions & 6 deletions include/small_gicp/util/downsampling_omp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,19 +39,15 @@ std::shared_ptr<OutputPointCloud> voxelgrid_sampling_omp(const InputPointCloud&
continue;
}
// Compute voxel coord bits (0|1bit, z|21bit, y|21bit, x|21bit)
const std::uint64_t bits = //
const std::uint64_t bits = //
(static_cast<std::uint64_t>(coord[0] & coord_bit_mask) << (coord_bit_size * 0)) | //
(static_cast<std::uint64_t>(coord[1] & coord_bit_mask) << (coord_bit_size * 1)) | //
(static_cast<std::uint64_t>(coord[2] & coord_bit_mask) << (coord_bit_size * 2));
coord_pt[i] = {bits, i};
}

// Sort by voxel coords
quick_sort_omp(
coord_pt.begin(),
coord_pt.end(),
[](const auto& lhs, const auto& rhs) { return lhs.first < rhs.first; },
num_threads);
quick_sort_omp(coord_pt.begin(), coord_pt.end(), [](const auto& lhs, const auto& rhs) { return lhs.first < rhs.first; }, num_threads);

auto downsampled = std::make_shared<OutputPointCloud>();
traits::resize(*downsampled, traits::size(points));
Expand Down
23 changes: 20 additions & 3 deletions src/python/align.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,8 @@ void define_align(py::module& m) {
double downsampling_resolution,
double max_correspondence_distance,
int num_threads,
int max_iterations) {
int max_iterations,
bool verbose) {
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 @@ -60,6 +61,8 @@ void define_align(py::module& m) {
setting.downsampling_resolution = downsampling_resolution;
setting.max_correspondence_distance = max_correspondence_distance;
setting.num_threads = num_threads;
setting.max_iterations = max_iterations;
setting.verbose = verbose;

std::vector<Eigen::Vector4d> target(target_points.rows());
if (target_points.cols() == 3) {
Expand Down Expand Up @@ -94,6 +97,7 @@ void define_align(py::module& m) {
py::arg("max_correspondence_distance") = 1.0,
py::arg("num_threads") = 1,
py::arg("max_iterations") = 20,
py::arg("verbose") = false,
R"pbdoc(
Align two point clouds using various ICP-like algorithms.
Expand All @@ -117,6 +121,8 @@ void define_align(py::module& m) {
Number of threads to use for parallel processing.
max_iterations : int = 20
Maximum number of iterations for the optimization algorithm.
verbose : bool = False
If True, print debug information during the optimization process.
Returns
-------
Expand All @@ -135,7 +141,8 @@ void define_align(py::module& m) {
const std::string& registration_type,
double max_correspondence_distance,
int num_threads,
int max_iterations) {
int max_iterations,
bool verbose) {
RegistrationSetting setting;
if (registration_type == "ICP") {
setting.type = RegistrationSetting::ICP;
Expand All @@ -149,6 +156,8 @@ void define_align(py::module& m) {
}
setting.max_correspondence_distance = max_correspondence_distance;
setting.num_threads = num_threads;
setting.max_iterations = max_iterations;
setting.verbose = verbose;

if (target_tree == nullptr) {
target_tree = std::make_shared<KdTree<PointCloud>>(target, KdTreeBuilderOMP(num_threads));
Expand All @@ -163,6 +172,7 @@ void define_align(py::module& m) {
py::arg("max_correspondence_distance") = 1.0,
py::arg("num_threads") = 1,
py::arg("max_iterations") = 20,
py::arg("verbose") = false,
R"pbdoc(
Align two point clouds using specified ICP-like algorithms, utilizing point cloud and KD-tree inputs.
Expand All @@ -184,6 +194,8 @@ void define_align(py::module& m) {
Number of threads to use for computation.
max_iterations : int = 20
Maximum number of iterations for the optimization algorithm.
verbose : bool = False
If True, print debug information during the optimization process.
Returns
-------
Expand All @@ -200,11 +212,13 @@ void define_align(py::module& m) {
const Eigen::Matrix4d& init_T_target_source,
double max_correspondence_distance,
int num_threads,
int max_iterations) {
int max_iterations,
bool verbose) {
Registration<GICPFactor, ParallelReductionOMP> registration;
registration.rejector.max_dist_sq = max_correspondence_distance * max_correspondence_distance;
registration.reduction.num_threads = num_threads;
registration.optimizer.max_iterations = max_iterations;
registration.optimizer.verbose = verbose;

return registration.align(target_voxelmap, source, target_voxelmap, Eigen::Isometry3d(init_T_target_source));
},
Expand All @@ -214,6 +228,7 @@ void define_align(py::module& m) {
py::arg("max_correspondence_distance") = 1.0,
py::arg("num_threads") = 1,
py::arg("max_iterations") = 20,
py::arg("verbose") = false,
R"pbdoc(
Align two point clouds using voxel-based GICP algorithm, utilizing a Gaussian Voxel Map.
Expand All @@ -231,6 +246,8 @@ void define_align(py::module& m) {
Number of threads to use for computation.
max_iterations : int = 20
Maximum number of iterations for the optimization algorithm.
verbose : bool = False
If True, print debug information during the optimization process.
Returns
-------
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 @@ -91,6 +91,7 @@ align(const PointCloud& target, const PointCloud& source, const KdTree<PointClou
registration.criteria.rotation_eps = setting.rotation_eps;
registration.criteria.translation_eps = setting.translation_eps;
registration.optimizer.max_iterations = setting.max_iterations;
registration.optimizer.verbose = setting.verbose;
return registration.align(target, source, target_tree, init_T);
}
case RegistrationSetting::PLANE_ICP: {
Expand All @@ -100,6 +101,7 @@ align(const PointCloud& target, const PointCloud& source, const KdTree<PointClou
registration.criteria.rotation_eps = setting.rotation_eps;
registration.criteria.translation_eps = setting.translation_eps;
registration.optimizer.max_iterations = setting.max_iterations;
registration.optimizer.verbose = setting.verbose;
return registration.align(target, source, target_tree, init_T);
}
case RegistrationSetting::GICP: {
Expand All @@ -109,6 +111,7 @@ align(const PointCloud& target, const PointCloud& source, const KdTree<PointClou
registration.criteria.rotation_eps = setting.rotation_eps;
registration.criteria.translation_eps = setting.translation_eps;
registration.optimizer.max_iterations = setting.max_iterations;
registration.optimizer.verbose = setting.verbose;
return registration.align(target, source, target_tree, init_T);
}
case RegistrationSetting::VGICP: {
Expand All @@ -129,6 +132,7 @@ RegistrationResult align(const GaussianVoxelMap& target, const PointCloud& sourc
registration.criteria.rotation_eps = setting.rotation_eps;
registration.criteria.translation_eps = setting.translation_eps;
registration.optimizer.max_iterations = setting.max_iterations;
registration.optimizer.verbose = setting.verbose;
return registration.align(target, source, target, init_T);
}

Expand Down

0 comments on commit 45b0b29

Please sign in to comment.