From b8b72819c143016b5abe5c9faab0567126be4f45 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 7 Sep 2013 16:49:51 +1000 Subject: [PATCH] AP_Compass: ignore COMPASS_ORIENT for internal compass this means if COMPASS_ORIENT is not 0 and the external compass fails to start on boot we don't end up with a bad compass orientation --- libraries/AP_Compass/AP_Compass_PX4.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_PX4.cpp b/libraries/AP_Compass/AP_Compass_PX4.cpp index fd0ad37208..99e38ada15 100644 --- a/libraries/AP_Compass/AP_Compass_PX4.cpp +++ b/libraries/AP_Compass/AP_Compass_PX4.cpp @@ -89,13 +89,13 @@ bool AP_Compass_PX4::read(void) // a noop on most boards _sum.rotate(MAG_BOARD_ORIENTATION); - // add user selectable orientation - _sum.rotate((enum Rotation)_orientation.get()); - // override any user setting of COMPASS_EXTERNAL _external.set(_is_external); - if (!_external) { + if (_external) { + // add user selectable orientation + _sum.rotate((enum Rotation)_orientation.get()); + } else { // add in board orientation from AHRS _sum.rotate(_board_orientation); }