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

feat(ekf_localizer): input ekf_dt to simple1dfilter #8622

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
Original file line number Diff line number Diff line change
Expand Up @@ -60,31 +60,27 @@ class Simple1DFilter
var_ = 1e9;
proc_var_x_c_ = 0.0;
};
void init(const double init_obs, const double obs_var, const rclcpp::Time & time)
void init(const double init_obs, const double obs_var)
{
x_ = init_obs;
var_ = obs_var;
latest_time_ = time;
initialized_ = true;
};
void update(const double obs, const double obs_var, const rclcpp::Time & time)
void update(const double obs, const double obs_var, const double dt)
{
if (!initialized_) {
init(obs, obs_var, time);
init(obs, obs_var);
return;
}

// Prediction step (current variance)
double dt = (time - latest_time_).seconds();
double proc_var_x_d = proc_var_x_c_ * dt * dt;
var_ = var_ + proc_var_x_d;

// Update step
double kalman_gain = var_ / (var_ + obs_var);
x_ = x_ + kalman_gain * (obs - x_);
var_ = (1 - kalman_gain) * var_;

latest_time_ = time;
};
void set_proc_var(const double proc_var) { proc_var_x_c_ = proc_var; }
[[nodiscard]] double get_x() const { return x_; }
Expand All @@ -95,7 +91,6 @@ class Simple1DFilter
double x_;
double var_;
double proc_var_x_c_;
rclcpp::Time latest_time_;
};

class EKFLocalizer : public rclcpp::Node
Expand Down
12 changes: 6 additions & 6 deletions localization/ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2018-2019 Autoware Foundation

Check notice on line 1 in localization/ekf_localizer/src/ekf_localizer.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

✅ No longer an issue: Code Duplication

The module no longer contains too many functions with similar structure
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -456,9 +456,9 @@
double pitch_var =
pose.pose.covariance[COV_IDX::PITCH_PITCH] * static_cast<double>(smoothing_step);

z_filter_.update(z, z_var, pose.header.stamp);
roll_filter_.update(rpy.x, roll_var, pose.header.stamp);
pitch_filter_.update(rpy.y, pitch_var, pose.header.stamp);
z_filter_.update(z, z_var, ekf_dt_);
roll_filter_.update(rpy.x, roll_var, ekf_dt_);
pitch_filter_.update(rpy.y, pitch_var, ekf_dt_);
}

void EKFLocalizer::init_simple_1d_filters(
Expand All @@ -473,9 +473,9 @@
double roll_var = pose.pose.covariance[COV_IDX::ROLL_ROLL];
double pitch_var = pose.pose.covariance[COV_IDX::PITCH_PITCH];

z_filter_.init(z, z_var, pose.header.stamp);
roll_filter_.init(rpy.x, roll_var, pose.header.stamp);
pitch_filter_.init(rpy.y, pitch_var, pose.header.stamp);
z_filter_.init(z, z_var);
roll_filter_.init(rpy.x, roll_var);
pitch_filter_.init(rpy.y, pitch_var);
}

/**
Expand Down
Loading