Browse Source

AP_Compass: fix compilation issue with declaring var after goto

gps-1.3.1
bugobliterator 3 years ago committed by Peter Barker
parent
commit
957da68da5
  1. 7
      libraries/AP_Compass/AP_Compass_RM3100.cpp

7
libraries/AP_Compass/AP_Compass_RM3100.cpp

@ -212,14 +212,13 @@ void AP_Compass_RM3100::timer() @@ -212,14 +212,13 @@ void AP_Compass_RM3100::timer()
// some RM3100 builds get the polarity wrong on one or more of the
// elements. By setting AP_RM3100_REVERSAL_MASK in hwdef.dat you
// can fix it without modifying the hardware
const uint8_t mask = AP_RM3100_REVERSAL_MASK;
if (mask & 1U) {
if (AP_RM3100_REVERSAL_MASK & 1U) {
magx = -magx;
}
if (mask & 2U) {
if (AP_RM3100_REVERSAL_MASK & 2U) {
magy = -magy;
}
if (mask & 4U) {
if (AP_RM3100_REVERSAL_MASK & 4U) {
magz = -magz;
}
#endif

Loading…
Cancel
Save