AP_InertialSensor: fixed accel cal simple to remove unused IMUs

when we change EAHRS_SENSORS to remove use of IMU from an external
AHRS we need to be able to zero the accel and gyro offsets to get
prearms to pass
This commit is contained in:
Andrew Tridgell 2024-02-13 15:15:21 +11:00 committed by Peter Barker
parent 8a392be078
commit dcee5e9693
1 changed files with 7 additions and 1 deletions

View File

@ -2464,7 +2464,7 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
}
// remove existing accel offsets and scaling
for (uint8_t k=0; k<num_accels; k++) {
for (uint8_t k=0; k<INS_MAX_INSTANCES; k++) {
_accel_offset(k).set(Vector3f());
_accel_scale(k).set(Vector3f(1,1,1));
new_accel_offset[k].zero();
@ -2552,6 +2552,12 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal()
caltemp_accel(k).set_and_save(get_temperature(k));
#endif
}
for (uint8_t k=num_accels; k<INS_MAX_INSTANCES; k++) {
_accel_offset(k).set_and_save(Vector3f());
_accel_scale(k).set_and_save(Vector3f());
_gyro_offset(k).set_and_save(Vector3f());
_accel_id(k).set_and_save(0);
}
#if AP_AHRS_ENABLED
// force trim to zero