From a1ea43461ad0c076d53f69c373a4e934af7a4f5f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 18 Sep 2014 17:32:03 +0900 Subject: [PATCH] Copter: typo fix for baro vs inav alt disparity definition --- ArduCopter/config.h | 4 ++-- ArduCopter/motors.pde | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 628bf53e1c..13134f1e1a 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -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 diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 21f2efd734..65af49887a 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -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")); }