Skip to content

Commit

Permalink
ekf2: properly reset IMU biases on calibration change (non-multi-EKF)
Browse files Browse the repository at this point in the history
 - this was working in the multi-EKF case using vehicle_imu, but missing
in sensor_combined
  • Loading branch information
dagar committed Apr 11, 2022
1 parent 8f89133 commit bb2ea57
Show file tree
Hide file tree
Showing 3 changed files with 29 additions and 1 deletion.
3 changes: 3 additions & 0 deletions msg/sensor_combined.msg
Original file line number Diff line number Diff line change
Expand Up @@ -18,3 +18,6 @@ uint8 CLIPPING_X = 1
uint8 CLIPPING_Y = 2
uint8 CLIPPING_Z = 4
uint8 accelerometer_clipping # bitfield indicating if there was any accelerometer clipping (per axis) during the sampling period

uint8 accel_calibration_count # Calibration changed counter. Monotonically increases whenever accelermeter calibration changes.
uint8 gyro_calibration_count # Calibration changed counter. Monotonically increases whenever rate gyro calibration changes.
22 changes: 22 additions & 0 deletions src/modules/ekf2/EKF2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -446,6 +446,28 @@ void EKF2::Run()
}

imu_dt = sensor_combined.gyro_integral_dt;

if (sensor_combined.accel_calibration_count != _accel_calibration_count) {

PX4_DEBUG("%d - resetting accelerometer bias", _instance);

_ekf.resetAccelBias();
_accel_calibration_count = sensor_combined.accel_calibration_count;

// reset bias learning
_accel_cal = {};
}

if (sensor_combined.gyro_calibration_count != _gyro_calibration_count) {

PX4_DEBUG("%d - resetting rate gyro bias", _instance);

_ekf.resetGyroBias();
_gyro_calibration_count = sensor_combined.gyro_calibration_count;

// reset bias learning
_gyro_cal = {};
}
}

if (_sensor_selection_sub.updated() || (_device_id_accel == 0 || _device_id_gyro == 0)) {
Expand Down
5 changes: 4 additions & 1 deletion src/modules/sensors/voted_sensors_update.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,8 @@ void VotedSensorsUpdate::imuPoll(struct sensor_combined_s &raw)
_last_sensor_data[uorb_index].gyro_rad[1] = gyro_rate(1);
_last_sensor_data[uorb_index].gyro_rad[2] = gyro_rate(2);
_last_sensor_data[uorb_index].gyro_integral_dt = imu_report.delta_angle_dt;

_last_sensor_data[uorb_index].accel_calibration_count = imu_report.accel_calibration_count;
_last_sensor_data[uorb_index].gyro_calibration_count = imu_report.gyro_calibration_count;

_last_accel_timestamp[uorb_index] = imu_report.timestamp_sample;

Expand Down Expand Up @@ -231,6 +232,8 @@ void VotedSensorsUpdate::imuPoll(struct sensor_combined_s &raw)
raw.accelerometer_integral_dt = _last_sensor_data[accel_best_index].accelerometer_integral_dt;
raw.gyro_integral_dt = _last_sensor_data[gyro_best_index].gyro_integral_dt;
raw.accelerometer_clipping = _last_sensor_data[accel_best_index].accelerometer_clipping;
raw.accel_calibration_count = _last_sensor_data[accel_best_index].accel_calibration_count;
raw.gyro_calibration_count = _last_sensor_data[gyro_best_index].gyro_calibration_count;

if ((accel_best_index != _accel.last_best_vote) || (_selection.accel_device_id != _accel_device_id[accel_best_index])) {
_accel.last_best_vote = (uint8_t)accel_best_index;
Expand Down

0 comments on commit bb2ea57

Please sign in to comment.