mirror of https://github.com/ArduPilot/ardupilot
Copter: typo fix for baro vs inav alt disparity definition
This commit is contained in:
parent
b8c74b7363
commit
a1ea43461a
|
@ -300,8 +300,8 @@
|
|||
#define FS_GCS_ENABLED_CONTINUE_MISSION 2
|
||||
|
||||
// pre-arm baro vs inertial nav max alt disparity
|
||||
#ifndef PREARM_MAX_ALT_DISPARITY_CMS
|
||||
# define PREARM_MAX_ALT_DISPARITY_CMS 100 // barometer and inertial nav altitude must be within this many centimeters
|
||||
#ifndef PREARM_MAX_ALT_DISPARITY_CM
|
||||
# define PREARM_MAX_ALT_DISPARITY_CM 100 // barometer and inertial nav altitude must be within this many centimeters
|
||||
#endif
|
||||
|
||||
// pre-arm check max velocity
|
||||
|
|
|
@ -536,7 +536,7 @@ static bool arm_checks(bool display_failure)
|
|||
|
||||
// check Baro & inav alt are within 1m
|
||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_BARO)) {
|
||||
if(fabs(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CMS) {
|
||||
if(fabs(inertial_nav.get_altitude() - baro_alt) > PREARM_MAX_ALT_DISPARITY_CM) {
|
||||
if (display_failure) {
|
||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Alt disparity"));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue