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

feat(imu_corrector): add gyro_bias estimation in diag #5054

Merged
Changes from all 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
8 changes: 8 additions & 0 deletions sensing/imu_corrector/src/gyro_bias_estimator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,14 @@ void GyroBiasEstimator::update_diagnostics(diagnostic_updater::DiagnosticStatusW
stat.add("gyro_bias", "Bias estimation is not yet ready because of insufficient data.");
stat.summary(diagnostic_msgs::msg::DiagnosticStatus::OK, "Not initialized");
} else {
stat.add("gyro_bias_x_for_imu_corrector", gyro_bias_.value().x);
stat.add("gyro_bias_y_for_imu_corrector", gyro_bias_.value().y);
stat.add("gyro_bias_z_for_imu_corrector", gyro_bias_.value().z);

stat.add("estimated_gyro_bias_x", gyro_bias_.value().x - angular_velocity_offset_x_);
stat.add("estimated_gyro_bias_y", gyro_bias_.value().y - angular_velocity_offset_y_);
stat.add("estimated_gyro_bias_z", gyro_bias_.value().z - angular_velocity_offset_z_);

// Validation
const bool is_bias_small_enough =
std::abs(gyro_bias_.value().x - angular_velocity_offset_x_) < gyro_bias_threshold_ &&
Expand Down