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)
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
34 #ifdef USE_SERIALRX_IBUS
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"
47 #include "telemetry/telemetry.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
)
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;
98 } else if (rxBytesToIgnore
) {
105 if (ibusFramePosition
== 0) {
106 if (isValidIa6bIbusPacketLength(c
)) {
107 ibusModel
= IBUS_MODEL_IA6B
;
110 ibusChannelOffset
= 2;
111 ibusChecksum
= 0xFFFF;
112 } else if ((ibusSyncByte
== 0) && (c
== 0x55)) {
113 ibusModel
= IBUS_MODEL_IA6
;
116 ibusChecksum
= 0x0000;
117 ibusChannelOffset
= 1;
118 } else if (ibusSyncByte
!= c
) {
123 ibus
[ibusFramePosition
] = (uint8_t)c
;
125 if (ibusFramePosition
== ibusFrameSize
- 1) {
126 lastFrameTimeUs
= now
;
127 ibusFrameDone
= true;
133 static bool isChecksumOkIa6(void)
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();
151 return isChecksumOkIa6b(ibus
, ibusFrameSize
);
155 static void updateChannelData(void)
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
) {
178 ibusFrameDone
= false;
180 if (checksumIsOk()) {
181 if (ibusModel
== IBUS_MODEL_IA6
|| ibusSyncByte
== IBUS_SERIAL_RX_PACKET_LENGTH
) {
183 frameStatus
= RX_FRAME_COMPLETE
;
184 rxRuntimeState
->lastRcFrameTimeUs
= lastFrameTimeUs
;
185 #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
187 rxBytesToIgnore
= respondToIbusRequest(ibus
);
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
)
206 rxRuntimeState
->channelCount
= IBUS_MAX_CHANNEL
;
207 rxRuntimeState
->rcReadRawFn
= ibusReadRawRC
;
208 rxRuntimeState
->rcFrameStatusFn
= ibusFrameStatus
;
210 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
216 bool portShared
= isSerialPortShared(portConfig
, FUNCTION_RX_SERIAL
, FUNCTION_TELEMETRY_IBUS
);
218 bool portShared
= false;
222 serialPort_t
*ibusPort
= openSerialPort(portConfig
->identifier
,
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)
233 initSharedIbusTelemetry(ibusPort
);
237 return ibusPort
!= NULL
;