mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: reduce to if healthy check from if-else
This commit is contained in:
parent
2fb002798c
commit
c126017035
|
@ -38,22 +38,21 @@ Compass::compass_cal_update()
|
||||||
bool
|
bool
|
||||||
Compass::start_calibration(uint8_t i, bool retry, bool autosave, float delay, bool autoreboot)
|
Compass::start_calibration(uint8_t i, bool retry, bool autosave, float delay, bool autoreboot)
|
||||||
{
|
{
|
||||||
if (healthy(i)) {
|
if (!healthy(i)) {
|
||||||
memset(_reports_sent,0,sizeof(_reports_sent));
|
|
||||||
if (!is_calibrating() && delay > 0.5f) {
|
|
||||||
AP_Notify::events.initiated_compass_cal = 1;
|
|
||||||
}
|
|
||||||
if (i == get_primary()) {
|
|
||||||
_calibrator[i].set_tolerance(8);
|
|
||||||
} else {
|
|
||||||
_calibrator[i].set_tolerance(16);
|
|
||||||
}
|
|
||||||
_calibrator[i].start(retry, autosave, delay);
|
|
||||||
_compass_cal_autoreboot = autoreboot;
|
|
||||||
return true;
|
|
||||||
} else {
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
memset(_reports_sent,0,sizeof(_reports_sent));
|
||||||
|
if (!is_calibrating() && delay > 0.5f) {
|
||||||
|
AP_Notify::events.initiated_compass_cal = 1;
|
||||||
|
}
|
||||||
|
if (i == get_primary()) {
|
||||||
|
_calibrator[i].set_tolerance(8);
|
||||||
|
} else {
|
||||||
|
_calibrator[i].set_tolerance(16);
|
||||||
|
}
|
||||||
|
_calibrator[i].start(retry, autosave, delay);
|
||||||
|
_compass_cal_autoreboot = autoreboot;
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
|
|
|
@ -1 +1 @@
|
||||||
Subproject commit 34e1d543e49c2756b8fa4b81ef30468497ea792a
|
Subproject commit 51858c810a3cb086d7c2041328bd32adec9fa724
|
Loading…
Reference in New Issue