Skip to content

Commit

Permalink
Removed unused paramters proc_cov_vx_d_, proc_cov_wz_d_, proc_cov_yaw…
Browse files Browse the repository at this point in the history
…_d, and proc_cov_yaw_bias_d_

Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 committed Nov 7, 2023
1 parent 72e96fc commit 15c5f8a
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -158,12 +158,6 @@ class EKFLocalizer : public rclcpp::Node
double ekf_rate_;
double ekf_dt_;

/* process noise variance for discrete model */
double proc_cov_yaw_d_; //!< @brief discrete yaw process noise
double proc_cov_yaw_bias_d_; //!< @brief discrete yaw bias process noise
double proc_cov_vx_d_; //!< @brief discrete process noise in d_vx=0
double proc_cov_wz_d_; //!< @brief discrete process noise in d_wz=0

bool is_activated_;

EKFDiagnosticInfo pose_diag_info_;
Expand Down
10 changes: 0 additions & 10 deletions localization/ekf_localizer/src/ekf_localizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,11 +49,6 @@ EKFLocalizer::EKFLocalizer(const std::string & node_name, const rclcpp::NodeOpti
pose_queue_(params_.pose_smoothing_steps),
twist_queue_(params_.twist_smoothing_steps)
{
/* convert to continuous to discrete */
proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0);
proc_cov_wz_d_ = std::pow(params_.proc_stddev_wz_c * ekf_dt_, 2.0);
proc_cov_yaw_d_ = std::pow(params_.proc_stddev_yaw_c * ekf_dt_, 2.0);

is_activated_ = false;

/* initialize ros system */
Expand Down Expand Up @@ -112,11 +107,6 @@ void EKFLocalizer::updatePredictFrequency()
ekf_rate_ = 1.0 / (get_clock()->now() - *last_predict_time_).seconds();
DEBUG_INFO(get_logger(), "[EKF] update ekf_rate_ to %f hz", ekf_rate_);
ekf_dt_ = 1.0 / std::max(ekf_rate_, 0.1);

/* Update discrete proc_cov*/
proc_cov_vx_d_ = std::pow(params_.proc_stddev_vx_c * ekf_dt_, 2.0);
proc_cov_wz_d_ = std::pow(params_.proc_stddev_wz_c * ekf_dt_, 2.0);
proc_cov_yaw_d_ = std::pow(params_.proc_stddev_yaw_c * ekf_dt_, 2.0);
}
}
last_predict_time_ = std::make_shared<const rclcpp::Time>(get_clock()->now());
Expand Down

0 comments on commit 15c5f8a

Please sign in to comment.