If RSSI Channel is set to Disabled when using S.Bus then generate RSS… (#5090)
[betaflight.git] / src / main / rx / xbus.c
blobf046056fb0495581289b7b27a208dbe316b37934
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
22 #include "platform.h"
24 #if defined(USE_SERIAL_RX) && defined(USE_SERIALRX_XBUS)
26 #include "common/crc.h"
28 #include "drivers/time.h"
30 #include "io/serial.h"
32 #ifdef USE_TELEMETRY
33 #include "telemetry/telemetry.h"
34 #endif
36 #include "rx/rx.h"
37 #include "rx/xbus.h"
40 // Serial driver for JR's XBus (MODE B) receiver
43 #define XBUS_CHANNEL_COUNT 12
44 #define XBUS_RJ01_CHANNEL_COUNT 12
46 // Frame is: ID(1 byte) + 12*channel(2 bytes) + CRC(2 bytes) = 27
47 #define XBUS_FRAME_SIZE_A1 27
48 #define XBUS_FRAME_SIZE_A2 35
51 #define XBUS_RJ01_FRAME_SIZE 33
52 #define XBUS_RJ01_MESSAGE_LENGTH 30
53 #define XBUS_RJ01_OFFSET_BYTES 3
55 #define XBUS_BAUDRATE 115200
56 #define XBUS_RJ01_BAUDRATE 250000
57 #define XBUS_MAX_FRAME_TIME 8000
59 // NOTE!
60 // This is actually based on ID+LENGTH (nibble each)
61 // 0xA - Multiplex ID (also used by JR, no idea why)
62 // 0x1 - 12 channels
63 // 0x2 - 16 channels
64 // However, the JR XG14 that is used for test at the moment
65 // does only use 0xA1 as its output. This is why the implementation
66 // is based on these numbers only. Maybe update this in the future?
67 #define XBUS_START_OF_FRAME_BYTE_A1 (0xA1) //12 channels
68 #define XBUS_START_OF_FRAME_BYTE_A2 (0xA2) //16 channels transfare, but only 12 channels use for
70 // Pulse length convertion from [0...4095] to µs:
71 // 800µs -> 0x000
72 // 1500µs -> 0x800
73 // 2200µs -> 0xFFF
74 // Total range is: 2200 - 800 = 1400 <==> 4095
75 // Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
76 #define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
78 static bool xBusFrameReceived = false;
79 static bool xBusDataIncoming = false;
80 static uint8_t xBusFramePosition;
81 static uint8_t xBusFrameLength;
82 static uint8_t xBusChannelCount;
83 static uint8_t xBusProvider;
86 // Use max values for ram areas
87 static volatile uint8_t xBusFrame[XBUS_FRAME_SIZE_A2]; //size 35 for 16 channels in xbus_Mode_B
88 static uint16_t xBusChannelData[XBUS_RJ01_CHANNEL_COUNT];
90 // Full RJ01 message CRC calculations
91 static uint8_t xBusRj01CRC8(uint8_t inData, uint8_t seed)
93 for (uint8_t bitsLeft = 8; bitsLeft > 0; bitsLeft--) {
94 const uint8_t temp = ((seed ^ inData) & 0x01);
96 if (temp == 0) {
97 seed >>= 1;
98 } else {
99 seed ^= 0x18;
100 seed >>= 1;
101 seed |= 0x80;
104 inData >>= 1;
107 return seed;
111 static void xBusUnpackModeBFrame(uint8_t offsetBytes)
113 // Calculate the CRC of the incoming frame
114 // Calculate on all bytes except the final two CRC bytes
115 const uint16_t inCrc = crc16_ccitt_update(0, (uint8_t*)&xBusFrame[offsetBytes], xBusFrameLength - 2);
117 // Get the received CRC
118 const uint16_t crc = (((uint16_t)xBusFrame[offsetBytes + xBusFrameLength - 2]) << 8) + ((uint16_t)xBusFrame[offsetBytes + xBusFrameLength - 1]);
120 if (crc == inCrc) {
121 // Unpack the data, we have a valid frame, only 12 channel unpack also when receive 16 channel
122 for (int i = 0; i < xBusChannelCount; i++) {
124 const uint8_t frameAddr = offsetBytes + 1 + i * 2;
125 uint16_t value = ((uint16_t)xBusFrame[frameAddr]) << 8;
126 value = value + ((uint16_t)xBusFrame[frameAddr + 1]);
128 // Convert to internal format
129 xBusChannelData[i] = XBUS_CONVERT_TO_USEC(value);
132 xBusFrameReceived = true;
136 static void xBusUnpackRJ01Frame(void)
138 // Calculate the CRC of the incoming frame
139 uint8_t outerCrc = 0;
140 uint8_t i = 0;
142 // When using the Align RJ01 receiver with
143 // a MODE B setting in the radio (XG14 tested)
144 // the MODE_B -frame is packed within some
145 // at the moment unknown bytes before and after:
146 // 0xA1 LEN __ 0xA1 12*(High + Low) CRC1 CRC2 + __ __ CRC_OUTER
147 // Compared to a standard MODE B frame that only
148 // contains the "middle" package.
149 // Hence, at the moment, the unknown header and footer
150 // of the RJ01 MODEB packages are discarded.
151 // However, the LAST byte (CRC_OUTER) is infact an 8-bit
152 // CRC for the whole package, using the Dallas-One-Wire CRC
153 // method.
154 // So, we check both these values as well as the provided length
155 // of the outer/full message (LEN)
158 // Check we have correct length of message
160 if (xBusFrame[1] != XBUS_RJ01_MESSAGE_LENGTH)
162 // Unknown package as length is not ok
163 return;
167 // CRC calculation & check for full message
169 for (i = 0; i < xBusFrameLength - 1; i++) {
170 outerCrc = xBusRj01CRC8(outerCrc, xBusFrame[i]);
173 if (outerCrc != xBusFrame[xBusFrameLength - 1])
175 // CRC does not match, skip this frame
176 return;
179 // Now unpack the "embedded MODE B frame"
180 xBusUnpackModeBFrame(XBUS_RJ01_OFFSET_BYTES);
183 // Receive ISR callback
184 static void xBusDataReceive(uint16_t c, void *data)
186 UNUSED(data);
188 uint32_t now;
189 static uint32_t xBusTimeLast, xBusTimeInterval;
191 // Check if we shall reset frame position due to time
192 now = micros();
193 xBusTimeInterval = now - xBusTimeLast;
194 xBusTimeLast = now;
195 if (xBusTimeInterval > XBUS_MAX_FRAME_TIME) {
196 xBusFramePosition = 0;
197 xBusDataIncoming = false;
200 // Check if we shall start a frame?
201 if (xBusFramePosition == 0) {
202 if (c == XBUS_START_OF_FRAME_BYTE_A1) {
203 xBusDataIncoming = true;
204 xBusFrameLength = XBUS_FRAME_SIZE_A1; //decrease framesize (when receiver change, otherwise board must reboot)
205 } else if (c == XBUS_START_OF_FRAME_BYTE_A2) {//16channel packet
206 xBusDataIncoming = true;
207 xBusFrameLength = XBUS_FRAME_SIZE_A2; //increase framesize
211 // Only do this if we are receiving to a frame
212 if (xBusDataIncoming == true) {
213 // Store in frame copy
214 xBusFrame[xBusFramePosition] = (uint8_t)c;
215 xBusFramePosition++;
218 // Done?
219 if (xBusFramePosition == xBusFrameLength) {
220 switch (xBusProvider) {
221 case SERIALRX_XBUS_MODE_B:
222 xBusUnpackModeBFrame(0);
223 FALLTHROUGH; //!!TODO - check this fall through is correct
224 case SERIALRX_XBUS_MODE_B_RJ01:
225 xBusUnpackRJ01Frame();
227 xBusDataIncoming = false;
228 xBusFramePosition = 0;
232 // Indicate time to read a frame from the data...
233 static uint8_t xBusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
235 UNUSED(rxRuntimeConfig);
237 if (!xBusFrameReceived) {
238 return RX_FRAME_PENDING;
241 xBusFrameReceived = false;
243 return RX_FRAME_COMPLETE;
246 static uint16_t xBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
248 uint16_t data;
250 // Deliver the data wanted
251 if (chan >= rxRuntimeConfig->channelCount) {
252 return 0;
255 data = xBusChannelData[chan];
257 return data;
260 bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
262 uint32_t baudRate;
264 switch (rxConfig->serialrx_provider) {
265 case SERIALRX_XBUS_MODE_B:
266 rxRuntimeConfig->channelCount = XBUS_CHANNEL_COUNT;
267 xBusFrameReceived = false;
268 xBusDataIncoming = false;
269 xBusFramePosition = 0;
270 baudRate = XBUS_BAUDRATE;
271 xBusFrameLength = XBUS_FRAME_SIZE_A1;
272 xBusChannelCount = XBUS_CHANNEL_COUNT;
273 xBusProvider = SERIALRX_XBUS_MODE_B;
274 break;
275 case SERIALRX_XBUS_MODE_B_RJ01:
276 rxRuntimeConfig->channelCount = XBUS_RJ01_CHANNEL_COUNT;
277 xBusFrameReceived = false;
278 xBusDataIncoming = false;
279 xBusFramePosition = 0;
280 baudRate = XBUS_RJ01_BAUDRATE;
281 xBusFrameLength = XBUS_RJ01_FRAME_SIZE;
282 xBusChannelCount = XBUS_RJ01_CHANNEL_COUNT;
283 xBusProvider = SERIALRX_XBUS_MODE_B_RJ01;
284 break;
285 default:
286 return false;
287 break;
290 rxRuntimeConfig->rxRefreshRate = 11000;
292 rxRuntimeConfig->rcReadRawFn = xBusReadRawRC;
293 rxRuntimeConfig->rcFrameStatusFn = xBusFrameStatus;
295 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
296 if (!portConfig) {
297 return false;
300 #ifdef USE_TELEMETRY
301 bool portShared = telemetryCheckRxPortShared(portConfig);
302 #else
303 bool portShared = false;
304 #endif
306 serialPort_t *xBusPort = openSerialPort(portConfig->identifier,
307 FUNCTION_RX_SERIAL,
308 xBusDataReceive,
309 NULL,
310 baudRate,
311 portShared ? MODE_RXTX : MODE_RX,
312 (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
315 #ifdef USE_TELEMETRY
316 if (portShared) {
317 telemetrySharedPort = xBusPort;
319 #endif
321 return xBusPort != NULL;
323 #endif