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

refactor(kalman_filter): make getter functions explicitly return values #1895

Merged
merged 9 commits into from
Sep 29, 2022
2 changes: 1 addition & 1 deletion .github/CODEOWNERS
Validating CODEOWNERS rules …
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ common/global_parameter_loader/** kenji.miyake@tier4.jp
common/goal_distance_calculator/** taiki.tanaka@tier4.jp
common/grid_map_utils/** maxime.clement@tier4.jp
common/interpolation/** fumiya.watanabe@tier4.jp takayuki.murooka@tier4.jp
common/kalman_filter/** yukihiro.saito@tier4.jp
common/kalman_filter/** koji.minoda@tier4.jp takeshi.ishita@tier4.jp yukihiro.saito@tier4.jp
common/motion_common/** christopherj.ho@gmail.com
common/motion_testing/** christopherj.ho@gmail.com
common/motion_utils/** satoshi.ota@tier4.jp taiki.tanaka@tier4.jp takayuki.murooka@tier4.jp yutaka.shimizu@tier4.jp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,15 +48,13 @@ class TimeDelayKalmanFilter : public KalmanFilter

/**
* @brief get latest time estimated state
* @param x latest time estimated state
*/
void getLatestX(Eigen::MatrixXd & x);
Eigen::MatrixXd getLatestX() const;

/**
* @brief get latest time estimation covariance
* @param P latest time estimation covariance
*/
void getLatestP(Eigen::MatrixXd & P);
Eigen::MatrixXd getLatestP() const;

/**
* @brief calculate kalman filter covariance by precision model with time delay. This is mainly
Expand Down
5 changes: 3 additions & 2 deletions common/kalman_filter/src/time_delay_kalman_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,8 +32,9 @@ void TimeDelayKalmanFilter::init(
}
}

void TimeDelayKalmanFilter::getLatestX(Eigen::MatrixXd & x) { x = x_.block(0, 0, dim_x_, 1); }
void TimeDelayKalmanFilter::getLatestP(Eigen::MatrixXd & P) { P = P_.block(0, 0, dim_x_, dim_x_); }
Eigen::MatrixXd TimeDelayKalmanFilter::getLatestX() const { return x_.block(0, 0, dim_x_, 1); }

Eigen::MatrixXd TimeDelayKalmanFilter::getLatestP() const { return P_.block(0, 0, dim_x_, dim_x_); }

bool TimeDelayKalmanFilter::predictWithDelay(
const Eigen::MatrixXd & x_next, const Eigen::MatrixXd & A, const Eigen::MatrixXd & Q)
Expand Down
40 changes: 14 additions & 26 deletions localization/ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -239,8 +239,7 @@ void EKFLocalizer::timerCallback()
void EKFLocalizer::showCurrentX()
{
if (show_debug_info_) {
Eigen::MatrixXd X(dim_x_, 1);
ekf_.getLatestX(X);
const Eigen::MatrixXd X = ekf_.getLatestX();
DEBUG_PRINT_MAT(X.transpose());
}
}
Expand Down Expand Up @@ -415,12 +414,10 @@ void EKFLocalizer::predictKinematicsModel()
* [ 0, 0, 0, 0, 0, 1]
*/

Eigen::MatrixXd X_curr(dim_x_, 1); // current state
ekf_.getLatestX(X_curr);
const Eigen::MatrixXd X_curr = ekf_.getLatestX();
DEBUG_PRINT_MAT(X_curr.transpose());

Eigen::MatrixXd P_curr;
ekf_.getLatestP(P_curr);
const Eigen::MatrixXd P_curr = ekf_.getLatestP();

const double dt = ekf_dt_;

Expand All @@ -431,8 +428,7 @@ void EKFLocalizer::predictKinematicsModel()
ekf_.predictWithDelay(X_next, A, Q);

// debug
Eigen::MatrixXd X_result(dim_x_, 1);
ekf_.getLatestX(X_result);
const Eigen::MatrixXd X_result = ekf_.getLatestX();
DEBUG_PRINT_MAT(X_result.transpose());
DEBUG_PRINT_MAT((X_result - X_curr).transpose());
}
Expand All @@ -449,8 +445,7 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar
pose.header.frame_id.c_str(), pose_frame_id_.c_str()),
2000);
}
Eigen::MatrixXd X_curr(dim_x_, 1); // current state
ekf_.getLatestX(X_curr);
const Eigen::MatrixXd X_curr = ekf_.getLatestX();
DEBUG_PRINT_MAT(X_curr.transpose());

constexpr int dim_y = 3; // pos_x, pos_y, yaw, depending on Pose output
Expand Down Expand Up @@ -496,9 +491,8 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar
Eigen::MatrixXd y_ekf(dim_y, 1);
y_ekf << ekf_.getXelement(delay_step * dim_x_ + IDX::X),
ekf_.getXelement(delay_step * dim_x_ + IDX::Y), ekf_yaw;
Eigen::MatrixXd P_curr, P_y;
ekf_.getLatestP(P_curr);
P_y = P_curr.block(0, 0, dim_y, dim_y);
const Eigen::MatrixXd P_curr = ekf_.getLatestP();
const Eigen::MatrixXd P_y = P_curr.block(0, 0, dim_y, dim_y);
if (!mahalanobisGate(pose_gate_dist_, y_ekf, y, P_y)) {
warning_.warnThrottle(
"[EKF] Pose measurement update, mahalanobis distance is over limit. ignore "
Expand All @@ -517,8 +511,7 @@ void EKFLocalizer::measurementUpdatePose(const geometry_msgs::msg::PoseWithCovar
ekf_.updateWithDelay(y, C, R, delay_step);

// debug
Eigen::MatrixXd X_result(dim_x_, 1);
ekf_.getLatestX(X_result);
const Eigen::MatrixXd X_result = ekf_.getLatestX();
DEBUG_PRINT_MAT(X_result.transpose());
DEBUG_PRINT_MAT((X_result - X_curr).transpose());
}
Expand All @@ -535,8 +528,7 @@ void EKFLocalizer::measurementUpdateTwist(
"twist frame_id must be base_link");
}

Eigen::MatrixXd X_curr(dim_x_, 1); // current state
ekf_.getLatestX(X_curr);
const Eigen::MatrixXd X_curr = ekf_.getLatestX();
DEBUG_PRINT_MAT(X_curr.transpose());

constexpr int dim_y = 2; // vx, wz
Expand Down Expand Up @@ -577,9 +569,8 @@ void EKFLocalizer::measurementUpdateTwist(
Eigen::MatrixXd y_ekf(dim_y, 1);
y_ekf << ekf_.getXelement(delay_step * dim_x_ + IDX::VX),
ekf_.getXelement(delay_step * dim_x_ + IDX::WZ);
Eigen::MatrixXd P_curr, P_y;
ekf_.getLatestP(P_curr);
P_y = P_curr.block(4, 4, dim_y, dim_y);
const Eigen::MatrixXd P_curr = ekf_.getLatestP();
const Eigen::MatrixXd P_y = P_curr.block(4, 4, dim_y, dim_y);
if (!mahalanobisGate(twist_gate_dist_, y_ekf, y, P_y)) {
warning_.warnThrottle(
"[EKF] Twist measurement update, mahalanobis distance is over limit. ignore "
Expand All @@ -599,8 +590,7 @@ void EKFLocalizer::measurementUpdateTwist(
ekf_.updateWithDelay(y, C, R, delay_step);

// debug
Eigen::MatrixXd X_result(dim_x_, 1);
ekf_.getLatestX(X_result);
const Eigen::MatrixXd X_result = ekf_.getLatestX();
DEBUG_PRINT_MAT(X_result.transpose());
DEBUG_PRINT_MAT((X_result - X_curr).transpose());
}
Expand All @@ -611,10 +601,8 @@ void EKFLocalizer::measurementUpdateTwist(
void EKFLocalizer::publishEstimateResult()
{
rclcpp::Time current_time = this->now();
Eigen::MatrixXd X(dim_x_, 1);
Eigen::MatrixXd P(dim_x_, dim_x_);
ekf_.getLatestX(X);
ekf_.getLatestP(P);
const Eigen::MatrixXd X = ekf_.getLatestX();
const Eigen::MatrixXd P = ekf_.getLatestP();

/* publish latest pose */
pub_pose_->publish(current_ekf_pose_);
Expand Down