Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
Messages
Services
Plugins
Recent questions tagged autoware_imu_corrector at Robotics Stack Exchange
Package Summary
| Tags | No category tags. |
| Version | 0.48.0 |
| License | Apache License 2.0 |
| Build type | AMENT_CMAKE |
| Use | RECOMMENDED |
Repository Summary
| Description | |
| Checkout URI | https://github.com/autowarefoundation/autoware_universe.git |
| VCS Type | git |
| VCS Version | main |
| Last Updated | 2025-12-03 |
| Dev Status | UNKNOWN |
| Released | UNRELEASED |
| Tags | planner ros calibration self-driving-car autonomous-driving autonomous-vehicles ros2 3d-map autoware |
| Contributing |
Help Wanted (-)
Good First Issues (-) Pull Requests to Review (-) |
Package Description
Additional Links
Maintainers
- Yamato Ando
- Taiki Yamada
Authors
- Yamato Ando
autoware_imu_corrector
imu_corrector
imu_corrector_node is a node that correct imu data.
- Correct yaw rate offset $b$ by reading the parameter.
- Correct yaw rate standard deviation $\sigma$ by reading the parameter.
- Correct yaw rate scale $s$ using NDT pose as a ground truth.
Mathematically, we assume the following equation:
\[\tilde{\omega}(t) = s(t) * \omega(t) + b(t) + n(t)\]where $\tilde{\omega}$ denotes observed angular velocity, $\omega$ denotes true angular velocity, $b$ denotes an offset, $s$ denotes the scale, and $n$ denotes a gaussian noise. We also assume that $n\sim\mathcal{N}(0, \sigma^2)$.
Input
| Name | Type | Description |
|---|---|---|
~input |
sensor_msgs::msg::Imu |
raw imu data |
Output
| Name | Type | Description |
|---|---|---|
~output |
sensor_msgs::msg::Imu |
corrected imu data |
Parameters
| Name | Type | Description |
|---|---|---|
angular_velocity_offset_x |
double | roll rate offset in imu_link [rad/s] |
angular_velocity_offset_y |
double | pitch rate offset imu_link [rad/s] |
angular_velocity_offset_z |
double | yaw rate offset imu_link [rad/s] |
angular_velocity_stddev_xx |
double | roll rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_yy |
double | pitch rate standard deviation imu_link [rad/s] |
angular_velocity_stddev_zz |
double | yaw rate standard deviation imu_link [rad/s] |
acceleration_stddev |
double | acceleration standard deviation imu_link [m/s^2] |
Note: The angular velocity offset values introduce a fixed compensation that is not considered in the gyro bias estimation. If the on_off_correction.correct_for_dynamic_bias flag and the on_off_correction.correct_for_static_bias flags are enabled, automatically the correct_for_static_bias will be disabled to avoid correction errors.
gyro_bias_estimator
gyro_bias_validator is a node that validates the bias of the gyroscope. It subscribes to the sensor_msgs::msg::Imu topic and validate if the bias of the gyroscope is within the specified range.
Note that the node calculates bias from the gyroscope data by averaging the data only when the vehicle is stopped.
Input
| Name | Type | Description |
|---|---|---|
~/input/imu_raw |
sensor_msgs::msg::Imu |
raw imu data |
~/input/pose |
geometry_msgs::msg::PoseWithCovarianceStamped |
ndt pose |
~/input/odometry |
nav_msgs::msg::Odometry |
odometry data |
Note that the input pose is assumed to be accurate enough. For example when using NDT, we assume that the NDT is appropriately converged.
Currently, it is possible to use methods other than NDT as a pose_source for Autoware, but less accurate methods are not suitable for IMU bias estimation.
In the future, with careful implementation for pose errors, the IMU bias estimated by NDT could potentially be used not only for validation but also for online calibration.
The Extended Kalman Filter (EKF) is used for scale estimation. The NDT pose is used as ground truth, and we assume it’s accurate enough to provide long-term convergence for the correct scale observation.
Output
| Name | Type | Description |
|---|---|---|
~/output/gyro_bias |
geometry_msgs::msg::Vector3Stamped |
bias of the gyroscope [rad/s] |
~/output/gyro_scale |
geometry_msgs::msg::Vector3Stamped |
estimated scale of the gyroscope [no units] |
Parameters (Bias estimation)
Note that this node also uses angular_velocity_offset_x, angular_velocity_offset_y, angular_velocity_offset_z parameters from imu_corrector.param.yaml.
| Name | Type | Description |
|---|---|---|
gyro_bias_threshold |
double | threshold of the bias of the gyroscope [rad/s] |
timer_callback_interval_sec |
double | seconds about the timer callback function [sec] |
diagnostics_updater_interval_sec |
double | period of the diagnostics updater [sec] |
straight_motion_ang_vel_upper_limit |
double | upper limit of yaw angular velocity, beyond which motion is not considered straight [rad/s] |
Parameters (Scale estimation)
| Name | Type | Description |
|---|---|---|
estimate_scale_init |
double | Initial value for scale estimation |
min_allowed_scale |
double | Minimum allowed scale value |
max_allowed_scale |
double | Maximum allowed scale value |
threshold_to_estimate_scale |
double | Minimum yaw rate required to estimate scale |
percentage_scale_rate_allow_correct |
double | Allowed percentage change with respect to current scale for correction |
alpha |
double | Filter coefficient for scale (complementary filter) |
delay_gyro_ms |
int | Delay applied to gyro data in milliseconds |
samples_filter_pose_rate |
int | Number of samples for pose rate filtering |
File truncated at 100 lines see the full file
Changelog for package autoware_imu_corrector
0.48.0 (2025-11-18)
-
Merge remote-tracking branch 'origin/main' into humble
-
feat: on off scale and bias correction (#11314)
- feat: adding parameter to turn on or off scale and bias correction
- style(pre-commit): autofix
- chore: add parameter to turn on or off scale and bias correction in launcher
- chore: updating schema
- chore: add override parameters from file to enable disable scal bias
- chore: renamed params to enable disble scale bias correction
* chore: modified schema files ---------Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
-
feat: scale gyro estimation (#10724)
- feat: scale estimation for gyro on z axis added
- after precommit local
- wip: imu correction with scale and bias
- feat: added diagnostic messages when scale change
- monitoring bias and scale gyro status in diagnostics message
- style(pre-commit): autofix
- added scale and bias on purpose for testing
- style(pre-commit): autofix
- added flipped gyro scaled bas signal
- style(pre-commit): autofix
- fixed bias sign, removed flipped mod signal
- style(pre-commit): autofix
- added scale estimation update function
- style(pre-commit): autofix
- Added threshold to avoid estimation when vehicle is stopped
- style(pre-commit): autofix
- scale changes real time test
- changed parameters scale file
- style(pre-commit): autofix
- feat: new ekf scale estimation using angle
- changed offset used for testing
- bias rotated and not rotated used for angle scale estimation
- style(pre-commit): autofix
- added bias to publish and bias not rotated for scale estimation
- deleting commented lines and renaming bias variable
- style(pre-commit): autofix
- rewrites gyro correction to avoid confusion, adds filter to scale estimation
- style(pre-commit): autofix
- Adding limits for covariance ekf angle
- style(pre-commit): autofix
- removing unused functions
- new params to detect large scale changes
- style(pre-commit): autofix
- renaming node name and changed parameters boundaries
- style(pre-commit): autofix
- refactor: main function to estimate scale
- style(pre-commit): autofix
- refactoring variables
- style(pre-commit): autofix
- new: Added json file for parameters and refactoring
- style(pre-commit): autofix
- refactor variables
- Refactor variables
- style(pre-commit): autofix
- new: unittest for scale angle estimation
- style(pre-commit): autofix
- added dependencies to package xml
- style(pre-commit): autofix
- header files inside include directory refactored , tested functions now public
- style(pre-commit): autofix
- moved include files and code refactored
- style(pre-commit): autofix
- refactor add has value checking for variable
- refactor: removed debug vectors
- style(pre-commit): autofix
- refactor: published scale for angle must be divided
- refactor: added missing header file
- style(pre-commit): autofix
- refactor: added zero checking
- style(pre-commit): autofix
- refactor: use abs to perform comparison
- chore: added scale estimation description to readme
- style(pre-commit): autofix
- chore: readme grammar correction
- refactor: fix to pass CI
* fix: documentation changed ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: pre-commit-ci-lite[bot] <117423508+pre-commit-ci-lite[bot]@users.noreply.github.com>
File truncated at 100 lines see the full file
Package Dependencies
System Dependencies
Dependant Packages
| Name | Deps |
|---|---|
| deviation_evaluator |
Launch files
- launch/gyro_bias_estimator.launch.xml
-
- input_imu_raw [default: imu_raw]
- input_odom [default: odom]
- input_pose_ndt [default: pose_ndt]
- output_gyro_bias [default: gyro_bias]
- output_gyro_scale [default: gyro_scale]
- output_imu_scaled [default: imu_scaled]
- gyro_bias_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_bias_estimator.param.yaml]
- imu_corrector_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- gyro_scale_estimator_param_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]
- launch/imu_corrector.launch.xml
-
- input_topic [default: imu_raw]
- input_gyro_bias_topic [default: gyro_bias]
- input_gyro_scale_topic [default: gyro_scale]
- output_topic [default: imu_data]
- param_file [default: $(find-pkg-share autoware_imu_corrector)/config/imu_corrector.param.yaml]
- param_scale_file [default: $(find-pkg-share autoware_imu_corrector)/config/gyro_scale_estimator.param.yaml]