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

[WIP] Covariance Estimation #312

Draft
wants to merge 42 commits into
base: main
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from 41 commits
Commits
Show all changes
42 commits
Select commit Hold shift + click to select a range
6da4049
First trial, this is very ugly
tizianoGuadagnino Mar 25, 2024
88727be
Merge branch 'tiziano/covariance' into 296-autocompute-icp-covariance
tizianoGuadagnino Mar 25, 2024
e26b2f5
Start explosing covariance in ros...WIP
tizianoGuadagnino Mar 25, 2024
3eb2069
Fix and improve ROS visualization (#285)
nachovizzo Mar 25, 2024
747b28f
Start explosing covariance in ros...WIP
tizianoGuadagnino Mar 25, 2024
1836b34
Copy over the covariance
tizianoGuadagnino Mar 25, 2024
c0b45cf
Fix merge
tizianoGuadagnino Mar 25, 2024
a5aa930
More cosmesis
tizianoGuadagnino Mar 26, 2024
10d4cd8
Pybind the estimate
tizianoGuadagnino Mar 26, 2024
18a290a
Reshape the usings for my mental health
tizianoGuadagnino Mar 26, 2024
d1f3c86
Type aliasing on pybinded struct, I love it
tizianoGuadagnino Mar 26, 2024
c47b4a5
Getting the python side to dont complain
tizianoGuadagnino Mar 26, 2024
f44998a
Now also python doesn't cry
tizianoGuadagnino Mar 26, 2024
d01e041
Simplify python side
tizianoGuadagnino Mar 27, 2024
7c3442c
Update formula, now based on Barfoot et.al
tizianoGuadagnino Mar 27, 2024
463fbd8
Add the inverse operation
tizianoGuadagnino Mar 27, 2024
21d2c76
We now take into account the uncertanty of the prediction model
tizianoGuadagnino Mar 27, 2024
a20a098
Simplify
tizianoGuadagnino Mar 27, 2024
257f2b3
Now it makes sense
tizianoGuadagnino Mar 28, 2024
59b0277
First trial, this is very ugly
tizianoGuadagnino Mar 25, 2024
e26db50
Start explosing covariance in ros...WIP
tizianoGuadagnino Mar 25, 2024
bba7b94
Copy over the covariance
tizianoGuadagnino Mar 25, 2024
ee13b4f
Fix merge
tizianoGuadagnino Mar 25, 2024
177373f
More cosmesis
tizianoGuadagnino Mar 26, 2024
e54ebd1
Pybind the estimate
tizianoGuadagnino Mar 26, 2024
9e93219
Reshape the usings for my mental health
tizianoGuadagnino Mar 26, 2024
75d9b86
Type aliasing on pybinded struct, I love it
tizianoGuadagnino Mar 26, 2024
21c7972
Getting the python side to dont complain
tizianoGuadagnino Mar 26, 2024
5ec519b
Now also python doesn't cry
tizianoGuadagnino Mar 26, 2024
7d38a34
Simplify python side
tizianoGuadagnino Mar 27, 2024
c251278
Update formula, now based on Barfoot et.al
tizianoGuadagnino Mar 27, 2024
39ed3ba
Add the inverse operation
tizianoGuadagnino Mar 27, 2024
d94aae0
We now take into account the uncertanty of the prediction model
tizianoGuadagnino Mar 27, 2024
2a054b8
Simplify
tizianoGuadagnino Mar 27, 2024
bf8c377
Now it makes sense
tizianoGuadagnino Mar 28, 2024
89fd830
Merge remote-tracking branch 'refs/remotes/origin/296-autocompute-icp…
tizianoGuadagnino Mar 28, 2024
f512a0d
Consistent naming for the ICP system matrix
tizianoGuadagnino Mar 28, 2024
13fcb56
Add reference for equations, still the values are too high
tizianoGuadagnino Mar 28, 2024
280e9a4
Reshape and follow proper math
tizianoGuadagnino Apr 3, 2024
b33f27f
Merge branch 'main' into 296-autocompute-icp-covariance
tizianoGuadagnino Apr 3, 2024
19582b8
Fix isort
tizianoGuadagnino Apr 3, 2024
3589390
Better match comments
benemer Apr 8, 2024
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
77 changes: 52 additions & 25 deletions cpp/kiss_icp/core/Registration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@

#include <algorithm>
#include <cmath>
#include <functional>
#include <numeric>
#include <sophus/se3.hpp>
#include <sophus/so3.hpp>
Expand All @@ -41,8 +42,10 @@ using Matrix6d = Eigen::Matrix<double, 6, 6>;
using Matrix3_6d = Eigen::Matrix<double, 3, 6>;
using Vector6d = Eigen::Matrix<double, 6, 1>;
} // namespace Eigen
using Associations = std::vector<std::pair<Eigen::Vector3d, Eigen::Vector3d>>;
using LinearSystem = std::pair<Eigen::Matrix6d, Eigen::Vector6d>;

using Correspondence = std::pair<Eigen::Vector3d, Eigen::Vector3d>;
using Associations = std::vector<Correspondence>;
using LinearSystem = std::tuple<Eigen::Matrix6d, Eigen::Vector6d, double>;

namespace {
inline double square(double x) { return x * x; }
Expand Down Expand Up @@ -120,7 +123,7 @@ Associations FindAssociations(const std::vector<Eigen::Vector3d> &points,
return associations;
}

LinearSystem BuildLinearSystem(const Associations &associations, double kernel) {
LinearSystem BuildLinearSystem(const Associations &associations, const double kernel_threshold) {
auto compute_jacobian_and_residual = [](auto association) {
const auto &[source, target] = association;
const Eigen::Vector3d residual = source - target;
Expand All @@ -131,38 +134,59 @@ LinearSystem BuildLinearSystem(const Associations &associations, double kernel)
};

auto sum_linear_systems = [](LinearSystem a, const LinearSystem &b) {
a.first += b.first;
a.second += b.second;
std::get<Eigen::Matrix6d>(a) += std::get<Eigen::Matrix6d>(b);
std::get<Eigen::Vector6d>(a) += std::get<Eigen::Vector6d>(b);
std::get<double>(a) += std::get<double>(b);
return a;
};

auto GM_weight = [&](double residual2) { return square(kernel) / square(kernel + residual2); };
auto GM_kernel = [&](double residual2) {
return square(kernel_threshold) / square(kernel_threshold + residual2);
};

using associations_iterator = Associations::const_iterator;
const auto &[JTJ, JTr] = tbb::parallel_reduce(
const auto &[JTJ, JTr, chi_square] = tbb::parallel_reduce(
// Range
tbb::blocked_range<associations_iterator>{associations.cbegin(), associations.cend()},
// Identity
LinearSystem(Eigen::Matrix6d::Zero(), Eigen::Vector6d::Zero()),
LinearSystem(Eigen::Matrix6d::Zero(), Eigen::Vector6d::Zero(), 0.0),
// 1st Lambda: Parallel computation
[&](const tbb::blocked_range<associations_iterator> &r, LinearSystem J) -> LinearSystem {
return std::transform_reduce(
r.begin(), r.end(), J, sum_linear_systems, [&](const auto &association) {
const auto &[J_r, residual] = compute_jacobian_and_residual(association);
const double w = GM_weight(residual.squaredNorm());
return LinearSystem(J_r.transpose() * w * J_r, // JTJ
J_r.transpose() * w * residual); // JTr
const double chi_square = residual.squaredNorm();
const double w = GM_kernel(chi_square);
return LinearSystem(J_r.transpose() * w * J_r, // JTJ
J_r.transpose() * w * residual, chi_square); // JTr
});
},
// 2nd Lambda: Parallel reduction of the private Jacboians
sum_linear_systems);

return {JTJ, JTr};
return {JTJ, JTr, chi_square};
}
} // namespace

namespace kiss_icp {

Estimate::Estimate() : pose(), covariance(Eigen::Matrix6d::Zero()) {}
Estimate::Estimate(const Sophus::SE3d &T, const Eigen::Matrix6d &Sigma)
: pose(T), covariance(Sigma) {}

// Equations from figure 3 of https://arxiv.org/pdf/1906.07795.pdf
Estimate Estimate::inverse() const {
const auto Adj = pose.inverse().Adj();
return {pose.inverse(), Adj * covariance * Adj.transpose()};
}

Estimate operator*(Estimate lhs, const Estimate &rhs) {
lhs.pose *= rhs.pose;
const auto Adj = lhs.pose.Adj();
lhs.covariance += Adj * rhs.covariance * Adj.transpose();
benemer marked this conversation as resolved.
Show resolved Hide resolved
return lhs;
}

Registration::Registration(int max_num_iteration, double convergence_criterion, int max_num_threads)
: max_num_iterations_(max_num_iteration),
convergence_criterion_(convergence_criterion),
Expand All @@ -174,35 +198,38 @@ Registration::Registration(int max_num_iteration, double convergence_criterion,
tbb::global_control::max_allowed_parallelism, static_cast<size_t>(max_num_threads_));
}

Sophus::SE3d Registration::AlignPointsToMap(const std::vector<Eigen::Vector3d> &frame,
const VoxelHashMap &voxel_map,
const Sophus::SE3d &initial_guess,
double max_correspondence_distance,
double kernel) {
Estimate Registration::AlignPointsToMap(const std::vector<Eigen::Vector3d> &frame,
const VoxelHashMap &voxel_map,
const Estimate &initial_guess,
double max_correspondence_distance,
double kernel_threshold) {
if (voxel_map.Empty()) return initial_guess;

// Equation (9)
std::vector<Eigen::Vector3d> source = frame;
TransformPoints(initial_guess, source);
TransformPoints(initial_guess.pose, source);

// ICP-loop
Sophus::SE3d T_icp = Sophus::SE3d();
Estimate icp_correction;
for (int j = 0; j < max_num_iterations_; ++j) {
// Equation (10)
const auto associations = FindAssociations(source, voxel_map, max_correspondence_distance);
const auto &associations = FindAssociations(source, voxel_map, max_correspondence_distance);
// Equation (11)
const auto &[JTJ, JTr] = BuildLinearSystem(associations, kernel);
const Eigen::Vector6d dx = JTJ.ldlt().solve(-JTr);
const auto &[JTJ, JTr, chi_square] = BuildLinearSystem(associations, kernel_threshold);
const auto JTJ_inverse = JTJ.inverse();
const Eigen::Vector6d dx = -JTJ_inverse * JTr;
const Sophus::SE3d estimation = Sophus::SE3d::exp(dx);
icp_correction.pose = estimation * icp_correction.pose;
// Follow Ollila et.al. https://arxiv.org/pdf/2006.10005.pdf - Eq. (2) for sample covariance
// using an M estimator
icp_correction.covariance = 1.0 / static_cast<double>(associations.size()) * JTJ_inverse;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

What happens if associations is empty 🤔

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The linear system will explode so also dx will be garbage.

// Equation (12)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shall we remove all this equation comments ?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I wanted to keep it there until we don't decide to merge as a reference. I don't want this on main, but for now I think it is useful during the development if some of us wants to go a bit deeper in the computation.

TransformPoints(estimation, source);
// Update iterations
T_icp = estimation * T_icp;
// Termination criteria
if (dx.norm() < convergence_criterion_) break;
}
// Spit the final transformation
return T_icp * initial_guess;
return icp_correction * initial_guess;
}

} // namespace kiss_icp
21 changes: 16 additions & 5 deletions cpp/kiss_icp/core/Registration.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,16 +28,27 @@

#include "VoxelHashMap.hpp"

using CovarianceMatrixType = Eigen::Matrix<double, 6, 6>;

namespace kiss_icp {

struct Estimate {
benemer marked this conversation as resolved.
Show resolved Hide resolved
Estimate();
Estimate(const Sophus::SE3d &T, const CovarianceMatrixType &Sigma);
Sophus::SE3d pose;
CovarianceMatrixType covariance;
Estimate inverse() const;
friend Estimate operator*(Estimate lhs, const Estimate &rhs);
};

struct Registration {
explicit Registration(int max_num_iteration, double convergence_criterion, int max_num_threads);

Sophus::SE3d AlignPointsToMap(const std::vector<Eigen::Vector3d> &frame,
const VoxelHashMap &voxel_map,
const Sophus::SE3d &initial_guess,
double max_correspondence_distance,
double kernel);
Estimate AlignPointsToMap(const std::vector<Eigen::Vector3d> &frame,
const VoxelHashMap &voxel_map,
const Estimate &initial_guess,
double max_correspondence_distance,
double kernel_threshold);

int max_num_iterations_;
double convergence_criterion_;
Expand Down
44 changes: 23 additions & 21 deletions cpp/kiss_icp/pipeline/KissICP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,12 @@ KissICP::Vector3dVectorTuple KissICP::RegisterFrame(const std::vector<Eigen::Vec
// TODO(Nacho) Add some asserts here to sanitize the timestamps

// If not enough poses for the estimation, do not de-skew
const size_t N = poses().size();
const size_t N = estimates().size();
if (N <= 2) return frame;

// Estimate linear and angular velocities
const auto &start_pose = poses_[N - 2];
const auto &finish_pose = poses_[N - 1];
const auto &start_pose = estimates_[N - 2].pose;
const auto &finish_pose = estimates_[N - 1].pose;
return DeSkewScan(frame, timestamps, start_pose, finish_pose);
}();
return RegisterFrame(deskew_frame);
Expand All @@ -64,19 +64,18 @@ KissICP::Vector3dVectorTuple KissICP::RegisterFrame(const std::vector<Eigen::Vec

// Compute initial_guess for ICP
const auto prediction = GetPredictionModel();
const auto last_pose = !poses_.empty() ? poses_.back() : Sophus::SE3d();
const auto initial_guess = last_pose * prediction;

const auto last_estimate = !estimates_.empty() ? estimates_.back() : Estimate();
const auto initial_guess = last_estimate * prediction;
// Run icp
const Sophus::SE3d new_pose = registration_.AlignPointsToMap(source, //
local_map_, //
initial_guess, //
3.0 * sigma, //
sigma / 3.0);
const auto model_deviation = initial_guess.inverse() * new_pose;
const auto new_estimate = registration_.AlignPointsToMap(source, //
local_map_, //
initial_guess, //
3.0 * sigma, //
sigma / 3.0);
const auto model_deviation = (initial_guess.inverse() * new_estimate).pose;
adaptive_threshold_.UpdateModelDeviation(model_deviation);
local_map_.Update(frame_downsample, new_pose);
poses_.push_back(new_pose);
local_map_.Update(frame_downsample, new_estimate.pose);
estimates_.push_back(new_estimate);
return {frame, source};
}

Expand All @@ -94,16 +93,19 @@ double KissICP::GetAdaptiveThreshold() {
return adaptive_threshold_.ComputeThreshold();
}

Sophus::SE3d KissICP::GetPredictionModel() const {
Sophus::SE3d pred = Sophus::SE3d();
const size_t N = poses_.size();
if (N < 2) return pred;
return poses_[N - 2].inverse() * poses_[N - 1];
Estimate KissICP::GetPredictionModel() const {
Estimate prediction;
Copy link
Member

@benemer benemer Apr 8, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think renaming Estimate will also help here, because Estimate prediction looks a bit weird

const size_t N = estimates_.size();
if (N > 1) {
prediction.pose = (estimates_[N - 2].inverse() * estimates_[N - 1]).pose;
}
return prediction;
}

bool KissICP::HasMoved() {
if (poses_.empty()) return false;
const double motion = (poses_.front().inverse() * poses_.back()).translation().norm();
if (estimates_.empty()) return false;
const double motion =
(estimates_.front().pose.inverse() * estimates_.back().pose).translation().norm();
return motion > 5.0 * config_.min_motion_th;
}

Expand Down
6 changes: 3 additions & 3 deletions cpp/kiss_icp/pipeline/KissICP.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,17 +71,17 @@ class KissICP {
const std::vector<double> &timestamps);
Vector3dVectorTuple Voxelize(const std::vector<Eigen::Vector3d> &frame) const;
double GetAdaptiveThreshold();
Sophus::SE3d GetPredictionModel() const;
Estimate GetPredictionModel() const;
bool HasMoved();

public:
// Extra C++ API to facilitate ROS debugging
std::vector<Eigen::Vector3d> LocalMap() const { return local_map_.Pointcloud(); };
std::vector<Sophus::SE3d> poses() const { return poses_; };
std::vector<Estimate> estimates() const { return estimates_; };

private:
// KISS-ICP pipeline modules
std::vector<Sophus::SE3d> poses_;
std::vector<Estimate> estimates_;
KISSConfig config_;
Registration registration_;
VoxelHashMap local_map_;
Expand Down
34 changes: 19 additions & 15 deletions python/kiss_icp/kiss_icp.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,14 +26,14 @@
from kiss_icp.deskew import get_motion_compensator
from kiss_icp.mapping import get_voxel_hash_map
from kiss_icp.preprocess import get_preprocessor
from kiss_icp.registration import get_registration
from kiss_icp.registration import Estimate, get_registration
from kiss_icp.threshold import get_threshold_estimator
from kiss_icp.voxelization import voxel_down_sample


class KissICP:
def __init__(self, config: KISSConfig):
self.poses = []
self.estimates = []
self.config = config
self.compensator = get_motion_compensator(config)
self.adaptive_threshold = get_threshold_estimator(self.config)
Expand All @@ -43,7 +43,7 @@ def __init__(self, config: KISSConfig):

def register_frame(self, frame, timestamps):
# Apply motion compensation
frame = self.compensator.deskew_scan(frame, self.poses, timestamps)
frame = self.compensator.deskew_scan(frame, self.estimates, timestamps)

# Preprocess the input cloud
frame = self.preprocess(frame)
Expand All @@ -56,21 +56,22 @@ def register_frame(self, frame, timestamps):

# Compute initial_guess for ICP
prediction = self.get_prediction_model()
last_pose = self.poses[-1] if self.poses else np.eye(4)
initial_guess = last_pose @ prediction
initial_guess = self.estimates[-1] if self.estimates else Estimate()
Copy link
Member

@benemer benemer Apr 8, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe better last_estimate? Since it is not yet the initial guess

initial_guess = initial_guess @ prediction

# Run ICP
new_pose = self.registration.align_points_to_map(
new_estimate = self.registration.align_points_to_map(
points=source,
voxel_map=self.local_map,
initial_guess=initial_guess,
max_correspondance_distance=3 * sigma,
kernel=sigma / 3,
)

self.adaptive_threshold.update_model_deviation(np.linalg.inv(initial_guess) @ new_pose)
self.local_map.update(frame_downsample, new_pose)
self.poses.append(new_pose)
pose_deviation = (initial_guess.inverse() @ new_estimate).pose
self.adaptive_threshold.update_model_deviation(pose_deviation)
self.local_map.update(frame_downsample, new_estimate.pose)
self.estimates.append(new_estimate)
return frame, source

def voxelize(self, iframe):
Expand All @@ -86,13 +87,16 @@ def get_adaptive_threshold(self):
)

def get_prediction_model(self):
if len(self.poses) < 2:
return np.eye(4)
return np.linalg.inv(self.poses[-2]) @ self.poses[-1]
prediction = Estimate()
if len(self.estimates) > 1:
pose_from = self.estimates[-2].pose
pose_to = self.estimates[-1].pose
prediction.pose = np.linalg.inv(pose_from) @ pose_to
return prediction

def has_moved(self):
if len(self.poses) < 1:
if len(self.estimates) < 1:
return False
compute_motion = lambda T1, T2: np.linalg.norm((np.linalg.inv(T1) @ T2)[:3, -1])
motion = compute_motion(self.poses[0], self.poses[-1])
compute_motion = lambda T1, T2: np.linalg.norm((T1.inverse() @ T2).pose[:3, -1])
motion = compute_motion(self.estimates[0], self.estimates[-1])
return motion > 5 * self.config.adaptive_threshold.min_motion_th
14 changes: 12 additions & 2 deletions python/kiss_icp/pipeline.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,9 @@ def __init__(
self.odometry = KissICP(config=self.config)
self.results = PipelineResults()
self.times = []
self.poses = self.odometry.poses
self.estimates = self.odometry.estimates
self.poses = []
self.covariances = []
self.has_gt = hasattr(self._dataset, "gt_poses")
self.gt_poses = self._dataset.gt_poses[self._first : self._last] if self.has_gt else None
self.dataset_name = self._dataset.__class__.__name__
Expand All @@ -89,6 +91,7 @@ def run(self):
self._write_gt_poses()
self._write_cfg()
self._write_log()
self._write_covariances()
return self.results

# Private interface ------
Expand All @@ -97,8 +100,12 @@ def _run_pipeline(self):
raw_frame, timestamps = self._next(idx)
start_time = time.perf_counter_ns()
source, keypoints = self.odometry.register_frame(raw_frame, timestamps)
self.poses.append(self.estimates[-1].pose)
self.covariances.append(self.estimates[-1].covariance)
self.times.append(time.perf_counter_ns() - start_time)
self.visualizer.update(source, keypoints, self.odometry.local_map, self.poses[-1])
self.visualizer.update(
source, keypoints, self.odometry.local_map, self.estimates[-1].pose
)

def _next(self, idx):
"""TODO: re-arrange this logic"""
Expand Down Expand Up @@ -165,6 +172,9 @@ def _write_gt_poses(self):
timestamps=self._get_frames_timestamps(),
)

def _write_covariances(self):
np.save(f"{self.results_dir}/covariances.npy", np.stack(self.covariances))

def _run_evaluation(self):
# Run estimation metrics evaluation, only when GT data was provided
if self.has_gt:
Expand Down
Loading
Loading