Auto updated submodule references [18-01-2025]
[betaflight.git] / src / main / rx / ibus.c
blobb76b523f75794924e43ccd17db927791b9d9ff53
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 lastFrameTimeUs = 0;
80 static bool isValidIa6bIbusPacketLength(uint8_t length)
82 return (length == IBUS_TELEMETRY_PACKET_LENGTH) || (length == IBUS_SERIAL_RX_PACKET_LENGTH);
85 // Receive ISR callback
86 static void ibusDataReceive(uint16_t c, void *data)
88 UNUSED(data);
90 static timeUs_t ibusTimeLast;
91 static uint8_t ibusFramePosition;
93 const timeUs_t now = microsISR();
95 if (cmpTimeUs(now, ibusTimeLast) > IBUS_FRAME_GAP) {
96 ibusFramePosition = 0;
97 rxBytesToIgnore = 0;
98 } else if (rxBytesToIgnore) {
99 rxBytesToIgnore--;
100 return;
103 ibusTimeLast = now;
105 if (ibusFramePosition == 0) {
106 if (isValidIa6bIbusPacketLength(c)) {
107 ibusModel = IBUS_MODEL_IA6B;
108 ibusSyncByte = c;
109 ibusFrameSize = c;
110 ibusChannelOffset = 2;
111 ibusChecksum = 0xFFFF;
112 } else if ((ibusSyncByte == 0) && (c == 0x55)) {
113 ibusModel = IBUS_MODEL_IA6;
114 ibusSyncByte = 0x55;
115 ibusFrameSize = 31;
116 ibusChecksum = 0x0000;
117 ibusChannelOffset = 1;
118 } else if (ibusSyncByte != c) {
119 return;
123 ibus[ibusFramePosition] = (uint8_t)c;
125 if (ibusFramePosition == ibusFrameSize - 1) {
126 lastFrameTimeUs = now;
127 ibusFrameDone = true;
128 } else {
129 ibusFramePosition++;
133 static bool isChecksumOkIa6(void)
135 uint8_t offset;
136 uint8_t i;
137 uint16_t chksum, rxsum;
138 chksum = ibusChecksum;
139 rxsum = ibus[ibusFrameSize - 2] + (ibus[ibusFrameSize - 1] << 8);
140 for (i = 0, offset = ibusChannelOffset; i < IBUS_MAX_SLOTS; i++, offset += 2) {
141 chksum += ibus[offset] + (ibus[offset + 1] << 8);
143 return chksum == rxsum;
146 static bool checksumIsOk(void)
148 if (ibusModel == IBUS_MODEL_IA6 ) {
149 return isChecksumOkIa6();
150 } else {
151 return isChecksumOkIa6b(ibus, ibusFrameSize);
155 static void updateChannelData(void)
157 uint8_t i;
158 uint8_t offset;
159 for (i = 0, offset = ibusChannelOffset; i < IBUS_MAX_SLOTS; i++, offset += 2) {
160 ibusChannelData[i] = ibus[offset] + ((ibus[offset + 1] & 0x0F) << 8);
162 //latest IBUS recievers are using prviously not used 4 bits on every channel to incresse total channel count
163 for (i = IBUS_MAX_SLOTS, offset = ibusChannelOffset + 1; i < IBUS_MAX_CHANNEL; i++, offset += 6) {
164 ibusChannelData[i] = ((ibus[offset] & 0xF0) >> 4) | (ibus[offset + 2] & 0xF0) | ((ibus[offset + 4] & 0xF0) << 4);
168 static uint8_t ibusFrameStatus(rxRuntimeState_t *rxRuntimeState)
170 UNUSED(rxRuntimeState);
172 uint8_t frameStatus = RX_FRAME_PENDING;
174 if (!ibusFrameDone) {
175 return frameStatus;
178 ibusFrameDone = false;
180 if (checksumIsOk()) {
181 if (ibusModel == IBUS_MODEL_IA6 || ibusSyncByte == IBUS_SERIAL_RX_PACKET_LENGTH) {
182 updateChannelData();
183 frameStatus = RX_FRAME_COMPLETE;
184 rxRuntimeState->lastRcFrameTimeUs = lastFrameTimeUs;
185 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
186 } else {
187 rxBytesToIgnore = respondToIbusRequest(ibus);
188 #endif
192 return frameStatus;
195 static float ibusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
197 UNUSED(rxRuntimeState);
198 return ibusChannelData[chan];
201 bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
203 UNUSED(rxConfig);
204 ibusSyncByte = 0;
206 rxRuntimeState->channelCount = IBUS_MAX_CHANNEL;
207 rxRuntimeState->rcReadRawFn = ibusReadRawRC;
208 rxRuntimeState->rcFrameStatusFn = ibusFrameStatus;
210 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
211 if (!portConfig) {
212 return false;
215 #ifdef USE_TELEMETRY
216 bool portShared = isSerialPortShared(portConfig, FUNCTION_RX_SERIAL, FUNCTION_TELEMETRY_IBUS);
217 #else
218 bool portShared = false;
219 #endif
221 rxBytesToIgnore = 0;
222 serialPort_t *ibusPort = openSerialPort(portConfig->identifier,
223 FUNCTION_RX_SERIAL,
224 ibusDataReceive,
225 NULL,
226 IBUS_BAUDRATE,
227 portShared ? MODE_RXTX : MODE_RX,
228 (rxConfig->serialrx_inverted ? SERIAL_INVERTED : SERIAL_NOT_INVERTED) | ((rxConfig->halfDuplex || portShared) ? SERIAL_BIDIR : 0)
231 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
232 if (portShared) {
233 initSharedIbusTelemetry(ibusPort);
235 #endif
237 return ibusPort != NULL;
240 #endif //SERIAL_RX