Skip to content

Commit

Permalink
fix(imu_corrector): remove force_update() in timer callback
Browse files Browse the repository at this point in the history
Signed-off-by: Takahisa.Ishikawa <[email protected]>
  • Loading branch information
Takahisa.Ishikawa committed Jan 16, 2025
1 parent ed1f844 commit 438b9de
Showing 1 changed file with 0 additions and 3 deletions.
3 changes: 0 additions & 3 deletions sensing/autoware_imu_corrector/src/gyro_bias_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@ GyroBiasEstimator::GyroBiasEstimator(const rclcpp::NodeOptions & options)
{
updater_.setHardwareID(get_name());
updater_.add("gyro_bias_validator", this, &GyroBiasEstimator::update_diagnostics);
// diagnostic_updater is designed to be updated at the same rate as the timer
updater_.setPeriod(diagnostics_updater_interval_sec_);

gyro_bias_estimation_module_ = std::make_unique<GyroBiasEstimationModule>();
Expand Down Expand Up @@ -182,8 +181,6 @@ void GyroBiasEstimator::timer_callback()
transform_vector3(gyro_bias_estimation_module_->get_bias_base_link(), *tf_base2imu_ptr);

validate_gyro_bias();
updater_.force_update();
updater_.setPeriod(diagnostics_updater_interval_sec_); // to reset timer inside the updater
}

void GyroBiasEstimator::validate_gyro_bias()
Expand Down

0 comments on commit 438b9de

Please sign in to comment.