From 2ba233942d3558f3fb5d68064555a10b2fc95621 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 3 Dec 2013 23:23:26 +0900 Subject: [PATCH] Copter: pre arm mag offset limit to 600 for PX4 --- ArduCopter/config.h | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index d153159918..07b322bdbd 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -356,6 +356,17 @@ #endif #endif +// max compass offset length (i.e. sqrt(offs_x^2+offs_y^2+offs_Z^2)) +#ifndef CONFIG_ARCH_BOARD_PX4FMU_V1 + #ifndef COMPASS_OFFSETS_MAX + # define COMPASS_OFFSETS_MAX 600 // PX4 onboard compass has high offsets + #endif +#else // APM1, APM2, SITL, FLYMAPLE, etc + #ifndef COMPASS_OFFSETS_MAX + # define COMPASS_OFFSETS_MAX 500 + #endif +#endif + ////////////////////////////////////////////////////////////////////////////// // OPTICAL_FLOW #ifndef OPTFLOW // sets global enabled/disabled flag for optflow (as seen in CLI)