commander: ignore calibration in HITL

The calibration is not found in HITL mode. Therefore, I suggest to
ignore this step and assume the calibration is fine.

This mostly fixes the preflight check indicator in QGC, arming was (for
some reason?) already possible.
This commit is contained in:
Julian Oes 2021-05-04 12:17:17 +02:00 committed by Daniel Agar
parent d3fd03a014
commit 648a21f11d
3 changed files with 18 additions and 3 deletions

View File

@ -65,7 +65,12 @@ bool PreFlightCheck::accelerometerCheck(orb_advert_t *mavlink_log_pub, vehicle_s
device_id = accel.get().device_id;
calibration_valid = (calibration::FindCalibrationIndex("ACC", device_id) >= 0);
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
calibration_valid = true;
} else {
calibration_valid = (calibration::FindCalibrationIndex("ACC", device_id) >= 0);
}
if (!calibration_valid) {
if (report_fail) {

View File

@ -64,7 +64,12 @@ bool PreFlightCheck::gyroCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &
device_id = gyro.get().device_id;
calibration_valid = (calibration::FindCalibrationIndex("GYRO", device_id) >= 0);
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
calibration_valid = true;
} else {
calibration_valid = (calibration::FindCalibrationIndex("GYRO", device_id) >= 0);
}
if (!calibration_valid) {
if (report_fail) {

View File

@ -66,7 +66,12 @@ bool PreFlightCheck::magnetometerCheck(orb_advert_t *mavlink_log_pub, vehicle_st
device_id = magnetometer.get().device_id;
calibration_valid = (calibration::FindCalibrationIndex("MAG", device_id) >= 0);
if (status.hil_state == vehicle_status_s::HIL_STATE_ON) {
calibration_valid = true;
} else {
calibration_valid = (calibration::FindCalibrationIndex("MAG", device_id) >= 0);
}
if (!calibration_valid) {
if (report_fail) {