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

fix(ekf_localizer): modified std deviation to deviation #1565

Merged
merged 3 commits into from
Aug 15, 2022
Merged
Show file tree
Hide file tree
Changes from 2 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
26 changes: 13 additions & 13 deletions localization/ekf_localizer/include/ekf_localizer/ekf_localizer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,46 +64,46 @@ class Simple1DFilter
{
initialized_ = false;
x_ = 0;
stddev_ = 1e9;
proc_stddev_x_c_ = 0.0;
dev_ = 1e9;
proc_dev_x_c_ = 0.0;
return;
};
void init(const double init_obs, const double obs_stddev, const rclcpp::Time time)
void init(const double init_obs, const double obs_dev, const rclcpp::Time time)
{
x_ = init_obs;
stddev_ = obs_stddev;
dev_ = obs_dev;
latest_time_ = time;
initialized_ = true;
return;
};
void update(const double obs, const double obs_stddev, const rclcpp::Time time)
void update(const double obs, const double obs_dev, const rclcpp::Time time)
{
if (!initialized_) {
init(obs, obs_stddev, time);
init(obs, obs_dev, time);
return;
}

// Prediction step (current stddev_)
double dt = (time - latest_time_).seconds();
double proc_stddev_x_d = proc_stddev_x_c_ * dt;
stddev_ = std::sqrt(stddev_ * stddev_ + proc_stddev_x_d * proc_stddev_x_d);
double proc_dev_x_d = proc_dev_x_c_ * dt;
cyn-liu marked this conversation as resolved.
Show resolved Hide resolved
dev_ = dev_ + proc_dev_x_d;

// Update step
double kalman_gain = stddev_ * stddev_ / (stddev_ * stddev_ + obs_stddev * obs_stddev);
double kalman_gain = dev_ / (dev_ + obs_dev);
x_ = x_ + kalman_gain * (obs - x_);
stddev_ = std::sqrt(1 - kalman_gain) * stddev_;
dev_ = (1 - kalman_gain) * dev_;

latest_time_ = time;
return;
};
void set_proc_stddev(const double proc_stddev) { proc_stddev_x_c_ = proc_stddev; }
void set_proc_dev(const double proc_dev) { proc_dev_x_c_ = proc_dev; }
double get_x() { return x_; }

private:
bool initialized_;
double x_;
double stddev_;
double proc_stddev_x_c_;
double dev_;
double proc_dev_x_c_;
rclcpp::Time latest_time_;
};

Expand Down
18 changes: 9 additions & 9 deletions localization/ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,9 +106,9 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti

initEKF();

z_filter_.set_proc_stddev(1.0);
roll_filter_.set_proc_stddev(0.1);
pitch_filter_.set_proc_stddev(0.1);
z_filter_.set_proc_dev(1.0);
roll_filter_.set_proc_dev(0.01);
pitch_filter_.set_proc_dev(0.01);

/* debug */
pub_debug_ = create_publisher<tier4_debug_msgs::msg::Float64MultiArrayStamped>("debug", 1);
Expand Down Expand Up @@ -764,11 +764,11 @@ void EKFLocalizer::updateSimple1DFilters(const geometry_msgs::msg::PoseWithCovar
tf2::fromMsg(pose.pose.pose.orientation, q_tf);
tf2::Matrix3x3(q_tf).getRPY(roll, pitch, yaw_tmp);

double z_stddev = std::sqrt(pose.pose.covariance[2 * 6 + 2]);
double roll_stddev = std::sqrt(pose.pose.covariance[3 * 6 + 3]);
double pitch_stddev = std::sqrt(pose.pose.covariance[4 * 6 + 4]);
double z_dev = pose.pose.covariance[2 * 6 + 2];
double roll_dev = pose.pose.covariance[3 * 6 + 3];
double pitch_dev = pose.pose.covariance[4 * 6 + 4];

z_filter_.update(z, z_stddev, pose.header.stamp);
roll_filter_.update(roll, roll_stddev, pose.header.stamp);
pitch_filter_.update(pitch, pitch_stddev, pose.header.stamp);
z_filter_.update(z, z_dev, pose.header.stamp);
roll_filter_.update(roll, roll_dev, pose.header.stamp);
pitch_filter_.update(pitch, pitch_dev, pose.header.stamp);
}