AP_Compass: fix compilation issue with declaring var after goto

This commit is contained in:
bugobliterator 2021-12-15 09:29:26 +11:00 committed by Peter Barker
parent 2205b95c99
commit 957da68da5

View File

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