Skip to content

Commit

Permalink
Renaming according to Ben's review
Browse files Browse the repository at this point in the history
  • Loading branch information
tizianoGuadagnino committed Nov 12, 2024
1 parent c4e34e3 commit 1a5a94c
Show file tree
Hide file tree
Showing 3 changed files with 13 additions and 12 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include <sophus/se3.hpp>

namespace {
double ModelError(const Sophus::SE3d &pose, const double max_range) {
double OdometryErrorInPointSpace(const Sophus::SE3d &pose, const double max_range) {
const double &theta = pose.so3().logAndTheta().theta;
const double &delta_rot = 2.0 * max_range * std::sin(theta / 2.0);
const double &delta_trans = pose.translation().norm();
Expand All @@ -43,22 +43,23 @@ CorrespondenceThreshold::CorrespondenceThreshold(const double map_discretization
max_range_(max_range),
use_adaptive_threshold_(use_adaptive_threshold),
fixed_threshold_(fixed_threshold),
model_sse_(0.0),
odom_sse_(0.0),
num_samples_(1e-8) {}

double CorrespondenceThreshold::ComputeThreshold() const {
if (!use_adaptive_threshold_) return fixed_threshold_;

const double moder_error_variance = std::sqrt(model_sse_ / num_samples_);
const double adaptive_threshold = 3.0 * (map_discretization_error_ + moder_error_variance);
const double sigma_odom = std::sqrt(odom_sse_ / num_samples_);
const double &sigma_map = map_discretization_error_; // <-- Renaming for clarity
const double adaptive_threshold = 3.0 * (sigma_map + sigma_odom);
return adaptive_threshold;
}

void CorrespondenceThreshold::UpdateModelError(const Sophus::SE3d &current_deviation) {
void CorrespondenceThreshold::UpdateOdometryError(const Sophus::SE3d &odometry_error) {
if (!use_adaptive_threshold_) return;

const double &model_error = ModelError(current_deviation, max_range_);
model_sse_ += model_error * model_error;
const double &odom_error_in_point_space = OdometryErrorInPointSpace(odometry_error, max_range_);
odom_sse_ += odom_error_in_point_space * odom_error_in_point_space;
num_samples_ += 1.0;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,12 @@ struct CorrespondenceThreshold {
const bool use_adaptive_threshold,
const double fixed_threshold);

void UpdateModelError(const Sophus::SE3d &current_deviation);
void UpdateOdometryError(const Sophus::SE3d &odometry_error);

double ComputeThreshold() const;

inline void Reset() {
model_sse_ = 0.0;
odom_sse_ = 0.0;
num_samples_ = 1e-8;
}

Expand All @@ -50,7 +50,7 @@ struct CorrespondenceThreshold {
double fixed_threshold_; // <-- Ignored if use_adaptive_threshold_ = true

// Local cache for computation
double model_sse_;
double odom_sse_;
double num_samples_;
};
} // namespace kinematic_icp
4 changes: 2 additions & 2 deletions cpp/kinematic_icp/pipeline/KinematicICP.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,10 @@ KinematicICP::Vector3dVectorTuple KinematicICP::RegisterFrame(
tau); // max_correspondence_dist

// Compute the difference between the prediction and the actual estimate
const auto model_deviation = (last_pose_ * relative_odometry).inverse() * new_pose;
const auto odometry_error = (last_pose_ * relative_odometry).inverse() * new_pose;

// Update step: threshold, local map and the last pose
correspondence_threshold_.UpdateModelError(model_deviation);
correspondence_threshold_.UpdateOdometryError(odometry_error);
local_map_.Update(frame_downsample, new_pose);
last_pose_ = new_pose;

Expand Down

0 comments on commit 1a5a94c

Please sign in to comment.