mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_Compass: flag compass cal as long expected delay
This commit is contained in:
parent
cec6f0e3d4
commit
025496f65e
@ -797,6 +797,9 @@ bool CompassCalibrator::calculate_orientation(void)
|
||||
return true;
|
||||
}
|
||||
|
||||
// this function is very slow
|
||||
hal.scheduler->expect_delay_ms(1000);
|
||||
|
||||
float variance[ROTATION_MAX] {};
|
||||
|
||||
for (enum Rotation r = ROTATION_NONE; r<ROTATION_MAX; r = (enum Rotation)(r+1)) {
|
||||
@ -863,6 +866,8 @@ bool CompassCalibrator::calculate_orientation(void)
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Mag(%u) new orientation: %u was %u %.1f", _compass_idx, besti, _orientation, _orientation_confidence);
|
||||
}
|
||||
|
||||
hal.scheduler->expect_delay_ms(0);
|
||||
|
||||
if (!pass) {
|
||||
set_status(COMPASS_CAL_BAD_ORIENTATION);
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user