From 76da561970ea879cb652eedd0124f6855237f442 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 15 Sep 2015 15:58:43 +0900 Subject: [PATCH] Copter: replace vehicle compass consistency check --- ArduCopter/config.h | 5 ----- ArduCopter/motors.cpp | 14 +------------- 2 files changed, 1 insertion(+), 18 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 2698df963b..540788089d 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -307,11 +307,6 @@ #endif #endif -// arming check's maximum acceptable vector difference between internal and external compass after vectors are normalized to field length of 1.0 -#ifndef COMPASS_ACCEPTABLE_VECTOR_DIFF - #define COMPASS_ACCEPTABLE_VECTOR_DIFF 0.75f // pre arm compass check will fail if internal vs external compass direction differ by more than 45 degrees - #endif - ////////////////////////////////////////////////////////////////////////////// // OPTICAL_FLOW #ifndef OPTFLOW diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index d40e91174a..4cceabbcc1 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -365,25 +365,13 @@ bool Copter::pre_arm_checks(bool display_failure) return false; } -#if COMPASS_MAX_INSTANCES > 1 // check all compasses point in roughly same direction - if (compass.get_count() > 1) { - Vector3f prime_mag_vec = compass.get_field(); - prime_mag_vec.normalize(); - for(uint8_t i=0; i COMPASS_ACCEPTABLE_VECTOR_DIFF) { + if (!compass.consistent()) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("PreArm: inconsistent compasses")); } return false; } - } - } -#endif }