mirror of https://github.com/ArduPilot/ardupilot
Copter: use disparity threshold define for pre-arm checks
There are two duplicate checks, one in the pre-arm checks (i.e. checks run every 15 seconds or so before the vehicle is armed) and one in the arming checks (run immediately before arming). The definition in the pre-arm checks was still using the old hardcoded value.
This commit is contained in:
parent
2b4f5fa79d
commit
d4cfb432ca
|
@ -243,7 +243,7 @@ static void pre_arm_checks(bool display_failure)
|
|||
return;
|
||||
}
|
||||
// check Baro & inav alt are within 1m
|
||||
if(fabs(inertial_nav.get_altitude() - baro_alt) > 100) {
|
||||
if(fabs(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: Alt disparity"));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue