Skip to content

Commit 09eda62

Browse files
feat(ekf_localizer): input ekf_dt to simple1dfilter (autowarefoundation#8622)
input ekf_dt to simple1dfilter Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> Co-authored-by: TaikiYamada4 <129915538+TaikiYamada4@users.noreply.github.com>
1 parent e709b10 commit 09eda62

File tree

2 files changed

+9
-14
lines changed

2 files changed

+9
-14
lines changed

localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp

+3-8
Original file line numberDiff line numberDiff line change
@@ -60,31 +60,27 @@ class Simple1DFilter
6060
var_ = 1e9;
6161
proc_var_x_c_ = 0.0;
6262
};
63-
void init(const double init_obs, const double obs_var, const rclcpp::Time & time)
63+
void init(const double init_obs, const double obs_var)
6464
{
6565
x_ = init_obs;
6666
var_ = obs_var;
67-
latest_time_ = time;
6867
initialized_ = true;
6968
};
70-
void update(const double obs, const double obs_var, const rclcpp::Time & time)
69+
void update(const double obs, const double obs_var, const double dt)
7170
{
7271
if (!initialized_) {
73-
init(obs, obs_var, time);
72+
init(obs, obs_var);
7473
return;
7574
}
7675

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

8280
// Update step
8381
double kalman_gain = var_ / (var_ + obs_var);
8482
x_ = x_ + kalman_gain * (obs - x_);
8583
var_ = (1 - kalman_gain) * var_;
86-
87-
latest_time_ = time;
8884
};
8985
void set_proc_var(const double proc_var) { proc_var_x_c_ = proc_var; }
9086
[[nodiscard]] double get_x() const { return x_; }
@@ -95,7 +91,6 @@ class Simple1DFilter
9591
double x_;
9692
double var_;
9793
double proc_var_x_c_;
98-
rclcpp::Time latest_time_;
9994
};
10095

10196
class EKFLocalizer : public rclcpp::Node

localization/ekf_localizer/src/ekf_localizer.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -456,9 +456,9 @@ void EKFLocalizer::update_simple_1d_filters(
456456
double pitch_var =
457457
pose.pose.covariance[COV_IDX::PITCH_PITCH] * static_cast<double>(smoothing_step);
458458

459-
z_filter_.update(z, z_var, pose.header.stamp);
460-
roll_filter_.update(rpy.x, roll_var, pose.header.stamp);
461-
pitch_filter_.update(rpy.y, pitch_var, pose.header.stamp);
459+
z_filter_.update(z, z_var, ekf_dt_);
460+
roll_filter_.update(rpy.x, roll_var, ekf_dt_);
461+
pitch_filter_.update(rpy.y, pitch_var, ekf_dt_);
462462
}
463463

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

476-
z_filter_.init(z, z_var, pose.header.stamp);
477-
roll_filter_.init(rpy.x, roll_var, pose.header.stamp);
478-
pitch_filter_.init(rpy.y, pitch_var, pose.header.stamp);
476+
z_filter_.init(z, z_var);
477+
roll_filter_.init(rpy.x, roll_var);
478+
pitch_filter_.init(rpy.y, pitch_var);
479479
}
480480

481481
/**

0 commit comments

Comments
 (0)