AP_RCProtocol: fixed decoding of SBUS switch channels

these are not used now, but may be in the future
This commit is contained in:
Andrew Tridgell 2018-11-28 08:11:21 +11:00
parent e3cd081064
commit 5baf4c42ea

View File

@ -174,9 +174,9 @@ bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values,
chancount = 18;
/* channel 17 (index 16) */
values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0)) * 1000 + 998;
values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0))?1998:998;
/* channel 18 (index 17) */
values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1)) * 1000 + 998;
values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1))?1998:998;
}
/* note the number of channels decoded */