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

Fetch Changes from KISS #26

Merged
merged 5 commits into from
Jan 9, 2025
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
2 changes: 1 addition & 1 deletion cpp/kinematic_icp/kiss_icp/kiss-icp.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,6 @@ if(CMAKE_VERSION VERSION_GREATER 3.24)
endif()

include(FetchContent)
FetchContent_Declare(kiss_icp URL https://github.com/PRBonn/kiss-icp/archive/refs/tags/v1.1.0.tar.gz SOURCE_SUBDIR
FetchContent_Declare(kiss_icp URL https://github.com/PRBonn/kiss-icp/archive/refs/tags/v1.2.0.tar.gz SOURCE_SUBDIR
cpp/kiss_icp)
FetchContent_MakeAvailable(kiss_icp)
24 changes: 10 additions & 14 deletions cpp/kinematic_icp/pipeline/KinematicICP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,9 +23,7 @@
#include "KinematicICP.hpp"

#include <Eigen/Core>
#include <kiss_icp/core/Deskew.hpp>
#include <kiss_icp/core/Preprocessing.hpp>
#include <kiss_icp/core/Registration.hpp>
#include <kiss_icp/core/VoxelHashMap.hpp>
#include <vector>

Expand All @@ -52,18 +50,16 @@ KinematicICP::Vector3dVectorTuple KinematicICP::RegisterFrame(
const std::vector<double> &timestamps,
const Sophus::SE3d &lidar_to_base,
const Sophus::SE3d &relative_odometry) {
const auto &deskew_frame = [&]() -> std::vector<Eigen::Vector3d> {
if (!config_.deskew || timestamps.empty()) return frame;
return kiss_icp::DeSkewScan(frame, timestamps,
lidar_to_base.inverse() * relative_odometry * lidar_to_base);
}();
const auto &deskew_frame_in_base = transform_points(deskew_frame, lidar_to_base);
// Preprocess the input cloud
const auto &cropped_frame =
kiss_icp::Preprocess(deskew_frame_in_base, config_.max_range, config_.min_range);

// Need to deskew in lidar frame
const Sophus::SE3d &relative_odometry_in_lidar =
lidar_to_base.inverse() * relative_odometry * lidar_to_base;
const auto &preprocessed_frame =
preprocessor_.Preprocess(frame, timestamps, relative_odometry_in_lidar);
// Give the frame in base frame
const auto &preprocessed_frame_in_base = transform_points(preprocessed_frame, lidar_to_base);
// Voxelize
const auto &[source, frame_downsample] = Voxelize(cropped_frame, config_.voxel_size);
const auto &[source, frame_downsample] =
Voxelize(preprocessed_frame_in_base, config_.voxel_size);

// Get adaptive_threshold
const double tau = correspondence_threshold_.ComputeThreshold();
Expand All @@ -85,6 +81,6 @@ KinematicICP::Vector3dVectorTuple KinematicICP::RegisterFrame(

// Return the (deskew) input raw scan (frame) and the points used for
// registration (source)
return {deskew_frame_in_base, source};
return {preprocessed_frame_in_base, source};
}
} // namespace kinematic_icp::pipeline
5 changes: 3 additions & 2 deletions cpp/kinematic_icp/pipeline/KinematicICP.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,8 @@

#include <Eigen/Core>
#include <cmath>
#include <kiss_icp/core/Threshold.hpp>
#include <kiss_icp/core/Preprocessing.hpp>
#include <kiss_icp/core/VoxelHashMap.hpp>
#include <kiss_icp/pipeline/KissICP.hpp>
#include <sophus/se3.hpp>
#include <tuple>
#include <vector>
Expand Down Expand Up @@ -76,6 +75,7 @@ class KinematicICP {
config.use_adaptive_threshold,
config.fixed_threshold),
config_(config),
preprocessor_(config.max_range, config.min_range, config.deskew, config.max_num_threads),
local_map_(config.voxel_size, config.max_range, config.max_points_per_voxel) {}

Vector3dVectorTuple RegisterFrame(const std::vector<Eigen::Vector3d> &frame,
Expand Down Expand Up @@ -104,6 +104,7 @@ class KinematicICP {
CorrespondenceThreshold correspondence_threshold_;
Config config_;
// KISS-ICP pipeline modules
kiss_icp::Preprocessor preprocessor_;
kiss_icp::VoxelHashMap local_map_;
};

Expand Down
29 changes: 9 additions & 20 deletions cpp/kinematic_icp/registration/Registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,10 @@
#include "Registration.hpp"

#include <tbb/blocked_range.h>
#include <tbb/concurrent_vector.h>
#include <tbb/global_control.h>
#include <tbb/info.h>
#include <tbb/parallel_for.h>
#include <tbb/parallel_reduce.h>
#include <tbb/task_arena.h>

Expand All @@ -38,7 +40,7 @@
#include <tuple>

using LinearSystem = std::pair<Eigen::Matrix2d, Eigen::Vector2d>;
using Correspondences = std::vector<std::pair<Eigen::Vector3d, Eigen::Vector3d>>;
using Correspondences = tbb::concurrent_vector<std::pair<Eigen::Vector3d, Eigen::Vector3d>>;

namespace {
constexpr double epsilon = std::numeric_limits<double>::min();
Expand All @@ -62,33 +64,20 @@ Correspondences DataAssociation(const std::vector<Eigen::Vector3d> &points,
const Sophus::SE3d &T,
const double max_correspondance_distance) {
using points_iterator = std::vector<Eigen::Vector3d>::const_iterator;
Correspondences associations;
associations.reserve(points.size());
associations = tbb::parallel_reduce(
Correspondences correspondences;
correspondences.reserve(points.size());
tbb::parallel_for(
// Range
tbb::blocked_range<points_iterator>{points.cbegin(), points.cend()},
// Identity
associations,
// 1st lambda: Parallel computation
[&](const tbb::blocked_range<points_iterator> &r, Correspondences res) -> Correspondences {
res.reserve(r.size());
[&](const tbb::blocked_range<points_iterator> &r) {
std::for_each(r.begin(), r.end(), [&](const auto &point) {
const auto &[closest_neighbor, distance] = voxel_map.GetClosestNeighbor(T * point);
if (distance < max_correspondance_distance) {
res.emplace_back(point, closest_neighbor);
correspondences.emplace_back(point, closest_neighbor);
}
});
return res;
},
// 2nd lambda: Parallel reduction
[](Correspondences a, const Correspondences &b) -> Correspondences {
a.insert(a.end(), //
std::make_move_iterator(b.cbegin()), //
std::make_move_iterator(b.cend()));
return a;
});

return associations;
return correspondences;
}

Eigen::Vector2d ComputePerturbation(const Correspondences &correspondences,
Expand Down
Loading