Change dcm_kp default to 25000
[betaflight.git] / src / main / rx / xbus.c
bloba9b860761828f3c76c5330b1465c6baa7642286e
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 #include "drivers/system.h"
26 #include "drivers/serial.h"
27 #include "drivers/serial_uart.h"
28 #include "io/serial.h"
30 #include "rx/rx.h"
31 #include "rx/xbus.h"
34 // Serial driver for JR's XBus (MODE B) receiver
37 #define XBUS_CHANNEL_COUNT 12
38 #define XBUS_RJ01_CHANNEL_COUNT 12
40 // Frame is: ID(1 byte) + 12*channel(2 bytes) + CRC(2 bytes) = 27
41 #define XBUS_FRAME_SIZE 27
43 #define XBUS_RJ01_FRAME_SIZE 33
44 #define XBUS_RJ01_MESSAGE_LENGTH 30
45 #define XBUS_RJ01_OFFSET_BYTES 3
47 #define XBUS_CRC_AND_VALUE 0x8000
48 #define XBUS_CRC_POLY 0x1021
50 #define XBUS_BAUDRATE 115200
51 #define XBUS_RJ01_BAUDRATE 250000
52 #define XBUS_MAX_FRAME_TIME 8000
54 // NOTE!
55 // This is actually based on ID+LENGTH (nibble each)
56 // 0xA - Multiplex ID (also used by JR, no idea why)
57 // 0x1 - 12 channels
58 // 0x2 - 16 channels
59 // However, the JR XG14 that is used for test at the moment
60 // does only use 0xA1 as its output. This is why the implementation
61 // is based on these numbers only. Maybe update this in the future?
62 #define XBUS_START_OF_FRAME_BYTE (0xA1)
64 // Pulse length convertion from [0...4095] to µs:
65 // 800µs -> 0x000
66 // 1500µs -> 0x800
67 // 2200µs -> 0xFFF
68 // Total range is: 2200 - 800 = 1400 <==> 4095
69 // Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
70 #define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
72 static bool xBusFrameReceived = false;
73 static bool xBusDataIncoming = false;
74 static uint8_t xBusFramePosition;
75 static uint8_t xBusFrameLength;
76 static uint8_t xBusChannelCount;
77 static uint8_t xBusProvider;
80 // Use max values for ram areas
81 static volatile uint8_t xBusFrame[XBUS_RJ01_FRAME_SIZE];
82 static uint16_t xBusChannelData[XBUS_RJ01_CHANNEL_COUNT];
84 static void xBusDataReceive(uint16_t c);
85 static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
87 bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
89 uint32_t baudRate;
91 switch (rxConfig->serialrx_provider) {
92 case SERIALRX_XBUS_MODE_B:
93 rxRuntimeConfig->channelCount = XBUS_CHANNEL_COUNT;
94 xBusFrameReceived = false;
95 xBusDataIncoming = false;
96 xBusFramePosition = 0;
97 baudRate = XBUS_BAUDRATE;
98 xBusFrameLength = XBUS_FRAME_SIZE;
99 xBusChannelCount = XBUS_CHANNEL_COUNT;
100 xBusProvider = SERIALRX_XBUS_MODE_B;
101 break;
102 case SERIALRX_XBUS_MODE_B_RJ01:
103 rxRuntimeConfig->channelCount = XBUS_RJ01_CHANNEL_COUNT;
104 xBusFrameReceived = false;
105 xBusDataIncoming = false;
106 xBusFramePosition = 0;
107 baudRate = XBUS_RJ01_BAUDRATE;
108 xBusFrameLength = XBUS_RJ01_FRAME_SIZE;
109 xBusChannelCount = XBUS_RJ01_CHANNEL_COUNT;
110 xBusProvider = SERIALRX_XBUS_MODE_B_RJ01;
111 break;
112 default:
113 return false;
114 break;
117 if (callback) {
118 *callback = xBusReadRawRC;
121 serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
122 if (!portConfig) {
123 return false;
126 serialPort_t *xBusPort = openSerialPort(portConfig->identifier, FUNCTION_RX_SERIAL, xBusDataReceive, baudRate, MODE_RX, SERIAL_NOT_INVERTED);
128 return xBusPort != NULL;
131 // The xbus mode B CRC calculations
132 static uint16_t xBusCRC16(uint16_t crc, uint8_t value)
134 uint8_t i;
136 crc = crc ^ (int16_t)value << 8;
138 for (i = 0; i < 8; i++) {
139 if (crc & XBUS_CRC_AND_VALUE) {
140 crc = crc << 1 ^ XBUS_CRC_POLY;
141 } else {
142 crc = crc << 1;
145 return crc;
148 // Full RJ01 message CRC calculations
149 uint8_t xBusRj01CRC8(uint8_t inData, uint8_t seed)
151 uint8_t bitsLeft;
152 uint8_t temp;
154 for (bitsLeft = 8; bitsLeft > 0; bitsLeft--) {
155 temp = ((seed ^ inData) & 0x01);
157 if (temp == 0) {
158 seed >>= 1;
159 } else {
160 seed ^= 0x18;
161 seed >>= 1;
162 seed |= 0x80;
165 inData >>= 1;
168 return seed;
172 static void xBusUnpackModeBFrame(uint8_t offsetBytes)
174 // Calculate the CRC of the incoming frame
175 uint16_t crc = 0;
176 uint16_t inCrc = 0;
177 uint8_t i = 0;
178 uint16_t value;
179 uint8_t frameAddr;
181 // Calculate on all bytes except the final two CRC bytes
182 for (i = 0; i < XBUS_FRAME_SIZE - 2; i++) {
183 inCrc = xBusCRC16(inCrc, xBusFrame[i+offsetBytes]);
186 // Get the received CRC
187 crc = ((uint16_t)xBusFrame[offsetBytes + XBUS_FRAME_SIZE - 2]) << 8;
188 crc = crc + ((uint16_t)xBusFrame[offsetBytes + XBUS_FRAME_SIZE - 1]);
190 if (crc == inCrc) {
191 // Unpack the data, we have a valid frame
192 for (i = 0; i < xBusChannelCount; i++) {
194 frameAddr = offsetBytes + 1 + i * 2;
195 value = ((uint16_t)xBusFrame[frameAddr]) << 8;
196 value = value + ((uint16_t)xBusFrame[frameAddr + 1]);
198 // Convert to internal format
199 xBusChannelData[i] = XBUS_CONVERT_TO_USEC(value);
202 xBusFrameReceived = true;
207 static void xBusUnpackRJ01Frame(void)
209 // Calculate the CRC of the incoming frame
210 uint8_t outerCrc = 0;
211 uint8_t i = 0;
213 // When using the Align RJ01 receiver with
214 // a MODE B setting in the radio (XG14 tested)
215 // the MODE_B -frame is packed within some
216 // at the moment unknown bytes before and after:
217 // 0xA1 LEN __ 0xA1 12*(High + Low) CRC1 CRC2 + __ __ CRC_OUTER
218 // Compared to a standard MODE B frame that only
219 // contains the "middle" package.
220 // Hence, at the moment, the unknown header and footer
221 // of the RJ01 MODEB packages are discarded.
222 // However, the LAST byte (CRC_OUTER) is infact an 8-bit
223 // CRC for the whole package, using the Dallas-One-Wire CRC
224 // method.
225 // So, we check both these values as well as the provided length
226 // of the outer/full message (LEN)
229 // Check we have correct length of message
231 if (xBusFrame[1] != XBUS_RJ01_MESSAGE_LENGTH)
233 // Unknown package as length is not ok
234 return;
238 // CRC calculation & check for full message
240 for (i = 0; i < xBusFrameLength - 1; i++) {
241 outerCrc = xBusRj01CRC8(outerCrc, xBusFrame[i]);
244 if (outerCrc != xBusFrame[xBusFrameLength - 1])
246 // CRC does not match, skip this frame
247 return;
250 // Now unpack the "embedded MODE B frame"
251 xBusUnpackModeBFrame(XBUS_RJ01_OFFSET_BYTES);
254 // Receive ISR callback
255 static void xBusDataReceive(uint16_t c)
257 uint32_t now;
258 static uint32_t xBusTimeLast, xBusTimeInterval;
260 // Check if we shall reset frame position due to time
261 now = micros();
262 xBusTimeInterval = now - xBusTimeLast;
263 xBusTimeLast = now;
264 if (xBusTimeInterval > XBUS_MAX_FRAME_TIME) {
265 xBusFramePosition = 0;
266 xBusDataIncoming = false;
269 // Check if we shall start a frame?
270 if ((xBusFramePosition == 0) && (c == XBUS_START_OF_FRAME_BYTE)) {
271 xBusDataIncoming = true;
274 // Only do this if we are receiving to a frame
275 if (xBusDataIncoming == true) {
276 // Store in frame copy
277 xBusFrame[xBusFramePosition] = (uint8_t)c;
278 xBusFramePosition++;
281 // Done?
282 if (xBusFramePosition == xBusFrameLength) {
283 switch (xBusProvider) {
284 case SERIALRX_XBUS_MODE_B:
285 xBusUnpackModeBFrame(0);
286 case SERIALRX_XBUS_MODE_B_RJ01:
287 xBusUnpackRJ01Frame();
289 xBusDataIncoming = false;
290 xBusFramePosition = 0;
294 // Indicate time to read a frame from the data...
295 uint8_t xBusFrameStatus(void)
297 if (!xBusFrameReceived) {
298 return SERIAL_RX_FRAME_PENDING;
301 xBusFrameReceived = false;
303 return SERIAL_RX_FRAME_COMPLETE;
306 static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
308 uint16_t data;
310 // Deliver the data wanted
311 if (chan >= rxRuntimeConfig->channelCount) {
312 return 0;
315 data = xBusChannelData[chan];
317 return data;