From eaa0e36954524c4d957a409792cee134a34345d3 Mon Sep 17 00:00:00 2001 From: Olivier-ADLER Date: Thu, 27 Jun 2013 00:29:01 +0200 Subject: [PATCH] Copter: CompassMot current calibration Was using a hardcoded (330) value instead of COMPASS_MAGFIELD_EXPECTED define --- ArduCopter/setup.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 48abc52cda..9bfe9bb110 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -357,7 +357,7 @@ setup_compassmot(uint8_t argc, const Menu::arg *argv) interference_pct = motor_compensation.length() / (float)COMPASS_MAGFIELD_EXPECTED * 100.0f; }else{ // interference is impact/amp * (max current seen / max throttle seen) / mag field * 100 - interference_pct = motor_compensation.length() * (current_amps_max/throttle_pct_max) / 330.0f * 100.0f; + interference_pct = motor_compensation.length() * (current_amps_max/throttle_pct_max) / (float)COMPASS_MAGFIELD_EXPECTED * 100.0f; } cliSerial->printf_P(PSTR("\nInterference at full throttle is %d%% of mag field\n\n"),(int)interference_pct); }else{