Reset protocol level RX frame delta after reading
[betaflight.git] / src / main / rx / ibus.c
blob4088f532f7f85e840d5bea66d6b3767af145f793
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * Driver for IBUS (Flysky) receiver
23 * - initial implementation for MultiWii by Cesco/Pl¸schi
24 * - implementation for BaseFlight by Andreas (fiendie) Tacke
25 * - ported to CleanFlight by Konstantin (digitalentity) Sharlaimov
28 #include <stdbool.h>
29 #include <stdint.h>
30 #include <stdlib.h>
32 #include "platform.h"
34 #ifdef USE_SERIALRX_IBUS
36 #include "pg/rx.h"
38 #include "common/utils.h"
40 #include "drivers/serial.h"
41 #include "drivers/serial_uart.h"
42 #include "drivers/time.h"
44 #include "io/serial.h"
46 #ifdef USE_TELEMETRY
47 #include "telemetry/telemetry.h"
48 #endif
50 #include "rx/rx.h"
51 #include "rx/ibus.h"
52 #include "telemetry/ibus.h"
53 #include "telemetry/ibus_shared.h"
55 #define IBUS_MAX_CHANNEL 18
56 //In AFHDS there is 18 channels encoded in 14 slots (each slot is 2 byte long)
57 #define IBUS_MAX_SLOTS 14
58 #define IBUS_BUFFSIZE 32
59 #define IBUS_MODEL_IA6B 0
60 #define IBUS_MODEL_IA6 1
61 #define IBUS_FRAME_GAP 500
63 #define IBUS_BAUDRATE 115200
64 #define IBUS_TELEMETRY_PACKET_LENGTH (4)
65 #define IBUS_SERIAL_RX_PACKET_LENGTH (32)
67 static uint8_t ibusModel;
68 static uint8_t ibusSyncByte;
69 static uint8_t ibusFrameSize;
70 static uint8_t ibusChannelOffset;
71 static uint8_t rxBytesToIgnore;
72 static uint16_t ibusChecksum;
74 static bool ibusFrameDone = false;
75 static uint32_t ibusChannelData[IBUS_MAX_CHANNEL];
77 static uint8_t ibus[IBUS_BUFFSIZE] = { 0, };
78 static timeUs_t lastRcFrameTimeUs = 0;
80 static bool isValidIa6bIbusPacketLength(uint8_t length)
82 return (length == IBUS_TELEMETRY_PACKET_LENGTH) || (length == IBUS_SERIAL_RX_PACKET_LENGTH);
86 // Receive ISR callback
87 static void ibusDataReceive(uint16_t c, void *data)
89 UNUSED(data);
91 static timeUs_t ibusTimeLast;
92 static uint8_t ibusFramePosition;
94 const timeUs_t ibusTime = microsISR();
96 if (cmpTimeUs(ibusTime, ibusTimeLast) > IBUS_FRAME_GAP) {
97 ibusFramePosition = 0;
98 rxBytesToIgnore = 0;
99 } else if (rxBytesToIgnore) {
100 rxBytesToIgnore--;
101 return;
104 ibusTimeLast = ibusTime;
106 if (ibusFramePosition == 0) {
107 if (isValidIa6bIbusPacketLength(c)) {
108 ibusModel = IBUS_MODEL_IA6B;
109 ibusSyncByte = c;
110 ibusFrameSize = c;
111 ibusChannelOffset = 2;
112 ibusChecksum = 0xFFFF;
113 } else if ((ibusSyncByte == 0) && (c == 0x55)) {
114 ibusModel = IBUS_MODEL_IA6;
115 ibusSyncByte = 0x55;
116 ibusFrameSize = 31;
117 ibusChecksum = 0x0000;
118 ibusChannelOffset = 1;
119 } else if (ibusSyncByte != c) {
120 return;
124 ibus[ibusFramePosition] = (uint8_t)c;
126 if (ibusFramePosition == ibusFrameSize - 1) {
127 lastRcFrameTimeUs = ibusTime;
128 ibusFrameDone = true;
129 } else {
130 ibusFramePosition++;
135 static bool isChecksumOkIa6(void)
137 uint8_t offset;
138 uint8_t i;
139 uint16_t chksum, rxsum;
140 chksum = ibusChecksum;
141 rxsum = ibus[ibusFrameSize - 2] + (ibus[ibusFrameSize - 1] << 8);
142 for (i = 0, offset = ibusChannelOffset; i < IBUS_MAX_SLOTS; i++, offset += 2) {
143 chksum += ibus[offset] + (ibus[offset + 1] << 8);
145 return chksum == rxsum;
149 static bool checksumIsOk(void) {
150 if (ibusModel == IBUS_MODEL_IA6 ) {
151 return isChecksumOkIa6();
152 } else {
153 return isChecksumOkIa6b(ibus, ibusFrameSize);
158 static void updateChannelData(void) {
159 uint8_t i;
160 uint8_t offset;
161 for (i = 0, offset = ibusChannelOffset; i < IBUS_MAX_SLOTS; i++, offset += 2) {
162 ibusChannelData[i] = ibus[offset] + ((ibus[offset + 1] & 0x0F) << 8);
164 //latest IBUS recievers are using prviously not used 4 bits on every channel to incresse total channel count
165 for (i = IBUS_MAX_SLOTS, offset = ibusChannelOffset + 1; i < IBUS_MAX_CHANNEL; i++, offset += 6) {
166 ibusChannelData[i] = ((ibus[offset] & 0xF0) >> 4) | (ibus[offset + 2] & 0xF0) | ((ibus[offset + 4] & 0xF0) << 4);
170 static uint8_t ibusFrameStatus(rxRuntimeState_t *rxRuntimeState)
172 UNUSED(rxRuntimeState);
174 uint8_t frameStatus = RX_FRAME_PENDING;
176 if (!ibusFrameDone) {
177 return frameStatus;
180 ibusFrameDone = false;
182 if (checksumIsOk()) {
183 if (ibusModel == IBUS_MODEL_IA6 || ibusSyncByte == IBUS_SERIAL_RX_PACKET_LENGTH) {
184 updateChannelData();
185 frameStatus = RX_FRAME_COMPLETE;
187 else
189 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
190 rxBytesToIgnore = respondToIbusRequest(ibus);
191 #endif
195 if (frameStatus != RX_FRAME_COMPLETE) {
196 lastRcFrameTimeUs = 0; // We received a frame but it wasn't valid new channel data
199 return frameStatus;
203 static uint16_t ibusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
205 UNUSED(rxRuntimeState);
206 return ibusChannelData[chan];
209 static timeUs_t ibusFrameTimeUs(void)
211 const timeUs_t result = lastRcFrameTimeUs;
212 lastRcFrameTimeUs = 0;
213 return result;
216 bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
218 UNUSED(rxConfig);
219 ibusSyncByte = 0;
221 rxRuntimeState->channelCount = IBUS_MAX_CHANNEL;
222 rxRuntimeState->rxRefreshRate = 20000; // TODO - Verify speed
224 rxRuntimeState->rcReadRawFn = ibusReadRawRC;
225 rxRuntimeState->rcFrameStatusFn = ibusFrameStatus;
226 rxRuntimeState->rcFrameTimeUsFn = ibusFrameTimeUs;
228 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
229 if (!portConfig) {
230 return false;
233 #ifdef USE_TELEMETRY
234 bool portShared = isSerialPortShared(portConfig, FUNCTION_RX_SERIAL, FUNCTION_TELEMETRY_IBUS);
235 #else
236 bool portShared = false;
237 #endif
240 rxBytesToIgnore = 0;
241 serialPort_t *ibusPort = openSerialPort(portConfig->identifier,
242 FUNCTION_RX_SERIAL,
243 ibusDataReceive,
244 NULL,
245 IBUS_BAUDRATE,
246 portShared ? MODE_RXTX : MODE_RX,
247 (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0)
250 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
251 if (portShared) {
252 initSharedIbusTelemetry(ibusPort);
254 #endif
256 return ibusPort != NULL;
259 #endif //SERIAL_RX