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
This commit is contained in:
Andrew Tridgell 2013-09-07 16:49:51 +10:00
parent 630095adaa
commit b8b72819c1

View File

@ -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);
}