Skip to content

Commit

Permalink
Removed force_update() since updater_ originaly updates diagnostics a…
Browse files Browse the repository at this point in the history
…utomatically.

Set the update peirod of diagnostics to be same to the timer_callback.
Changed words of the diagnostics message a bit.

Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 committed Jan 22, 2024
1 parent 4d9627e commit 818f636
Showing 1 changed file with 3 additions and 8 deletions.
11 changes: 3 additions & 8 deletions sensing/imu_corrector/src/gyro_bias_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,8 @@ GyroBiasEstimator::GyroBiasEstimator()
{
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(timer_callback_interval_sec_);

gyro_bias_estimation_module_ = std::make_unique<GyroBiasEstimationModule>();

Expand Down Expand Up @@ -107,7 +109,6 @@ void GyroBiasEstimator::timer_callback()
if (pose_buf_.empty()) {
is_bias_updated_ = false;
supplement_ = "pose_buf is empty";
updater_.force_update();
return;
}

Expand All @@ -123,7 +124,6 @@ void GyroBiasEstimator::timer_callback()
if (t1_rclcpp_time <= t0_rclcpp_time) {
is_bias_updated_ = false;
supplement_ = "pose_buf is not in chronological order";
updater_.force_update();
return;
}

Expand All @@ -141,7 +141,6 @@ void GyroBiasEstimator::timer_callback()
if (gyro_filtered.size() <= 1) {
is_bias_updated_ = false;
supplement_ = "gyro_filtered size is less than 2";
updater_.force_update();
return;
}

Expand All @@ -157,7 +156,6 @@ void GyroBiasEstimator::timer_callback()
if (!is_straight) {
is_bias_updated_ = false;
supplement_ = "yaw angular velocity is greater than straight_motion_ang_vel_upper_limit";
updater_.force_update();
return;
}

Expand All @@ -172,14 +170,11 @@ void GyroBiasEstimator::timer_callback()

is_bias_updated_ = false;
supplement_ = "tf betweeen base and imu is not available";

Check warning on line 172 in sensing/imu_corrector/src/gyro_bias_estimator.cpp

View workflow job for this annotation

GitHub Actions / spell-check-partial

Unknown word (betweeen)

Check warning on line 172 in sensing/imu_corrector/src/gyro_bias_estimator.cpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (betweeen)
updater_.force_update();
return;
}

gyro_bias_ =
transform_vector3(gyro_bias_estimation_module_->get_bias_base_link(), *tf_base2imu_ptr);

updater_.force_update();
}

geometry_msgs::msg::Vector3 GyroBiasEstimator::transform_vector3(
Expand Down Expand Up @@ -230,7 +225,7 @@ void GyroBiasEstimator::update_diagnostics(diagnostic_updater::DiagnosticStatusW
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Successfully updated");
}
else {
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Not updated");
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Paused update");
}
} else {
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::WARN,
Expand Down

0 comments on commit 818f636

Please sign in to comment.