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/>.
28 #ifdef USE_SERIALRX_FPORT
30 #include "build/debug.h"
32 #include "common/maths.h"
33 #include "common/utils.h"
35 #include "drivers/time.h"
37 #include "io/serial.h"
40 #include "telemetry/telemetry.h"
41 #include "telemetry/smartport.h"
46 #include "rx/frsky_crc.h"
48 #include "rx/sbus_channels.h"
51 #define FPORT_TIME_NEEDED_PER_FRAME_US 3000
52 #define FPORT_MAX_TELEMETRY_RESPONSE_DELAY_US 2000
53 #define FPORT_MIN_TELEMETRY_RESPONSE_DELAY_US 500
54 #define FPORT_MAX_TELEMETRY_AGE_MS 500
56 #define FPORT_TELEMETRY_MAX_CONSECUTIVE_TELEMETRY_FRAMES 2
58 #define FPORT_FRAME_MARKER 0x7E
60 #define FPORT_ESCAPE_CHAR 0x7D
61 #define FPORT_ESCAPE_MASK 0x20
63 #define FPORT_BAUDRATE 115200
65 #define FPORT_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO)
68 DEBUG_FPORT_FRAME_INTERVAL
= 0,
69 DEBUG_FPORT_FRAME_ERRORS
,
70 DEBUG_FPORT_FRAME_LAST_ERROR
,
71 DEBUG_FPORT_TELEMETRY_INTERVAL
,
75 DEBUG_FPORT_NO_ERROR
= 0,
76 DEBUG_FPORT_ERROR_TIMEOUT
,
77 DEBUG_FPORT_ERROR_OVERSIZE
,
78 DEBUG_FPORT_ERROR_SIZE
,
79 DEBUG_FPORT_ERROR_CHECKSUM
,
80 DEBUG_FPORT_ERROR_TYPE
,
81 DEBUG_FPORT_ERROR_TYPE_SIZE
,
85 FPORT_FRAME_TYPE_CONTROL
= 0x00,
86 FPORT_FRAME_TYPE_TELEMETRY_REQUEST
= 0x01,
87 FPORT_FRAME_TYPE_TELEMETRY_RESPONSE
= 0x81,
92 FPORT_FRAME_ID_NULL
= 0x00, // (master/slave)
93 FPORT_FRAME_ID_DATA
= 0x10, // (master/slave)
94 FPORT_FRAME_ID_READ
= 0x30, // (master)
95 FPORT_FRAME_ID_WRITE
= 0x31, // (master)
96 FPORT_FRAME_ID_RESPONSE
= 0x32, // (slave)
99 typedef struct fportControlData_s
{
100 sbusChannels_t channels
;
102 } fportControlData_t
;
104 typedef union fportData_s
{
105 fportControlData_t controlData
;
106 smartPortPayload_t telemetryData
;
109 typedef struct fportFrame_s
{
114 #ifdef USE_TELEMETRY_SMARTPORT
115 static const smartPortPayload_t emptySmartPortFrame
= { .frameId
= 0, .valueId
= 0, .data
= 0 };
118 #define FPORT_REQUEST_FRAME_LENGTH sizeof(fportFrame_t)
119 #define FPORT_RESPONSE_FRAME_LENGTH (sizeof(uint8_t) + sizeof(smartPortPayload_t))
121 #define FPORT_FRAME_PAYLOAD_LENGTH_CONTROL (sizeof(uint8_t) + sizeof(fportControlData_t))
122 #define FPORT_FRAME_PAYLOAD_LENGTH_TELEMETRY_REQUEST (sizeof(uint8_t) + sizeof(smartPortPayload_t))
124 #define NUM_RX_BUFFERS 3
125 #define BUFFER_SIZE (FPORT_REQUEST_FRAME_LENGTH + 2 * sizeof(uint8_t))
127 typedef struct fportBuffer_s
{
128 uint8_t data
[BUFFER_SIZE
];
130 timeUs_t frameStartTimeUs
;
133 static fportBuffer_t rxBuffer
[NUM_RX_BUFFERS
];
135 static volatile uint8_t rxBufferWriteIndex
= 0;
136 static volatile uint8_t rxBufferReadIndex
= 0;
138 static volatile timeUs_t lastTelemetryFrameReceivedUs
;
139 static volatile bool clearToSend
= false;
141 static volatile uint8_t framePosition
= 0;
143 static smartPortPayload_t
*mspPayload
= NULL
;
144 static timeUs_t lastRcFrameReceivedMs
= 0;
146 static serialPort_t
*fportPort
;
147 #ifdef USE_TELEMETRY_SMARTPORT
148 static bool telemetryEnabled
= false;
151 static void reportFrameError(uint8_t errorReason
)
153 static volatile uint16_t frameErrors
= 0;
157 DEBUG_SET(DEBUG_FPORT
, DEBUG_FPORT_FRAME_ERRORS
, frameErrors
);
158 DEBUG_SET(DEBUG_FPORT
, DEBUG_FPORT_FRAME_LAST_ERROR
, errorReason
);
161 // Receive ISR callback
162 static void fportDataReceive(uint16_t c
, void *data
)
166 static timeUs_t frameStartAt
= 0;
167 static bool escapedCharacter
= false;
168 static timeUs_t lastFrameReceivedUs
= 0;
169 static bool telemetryFrame
= false;
171 const timeUs_t currentTimeUs
= microsISR();
175 if (framePosition
> 1 && cmpTimeUs(currentTimeUs
, frameStartAt
) > FPORT_TIME_NEEDED_PER_FRAME_US
+ 500) {
176 reportFrameError(DEBUG_FPORT_ERROR_TIMEOUT
);
181 uint8_t val
= (uint8_t)c
;
183 if (val
== FPORT_FRAME_MARKER
) {
184 if (framePosition
> 1) {
185 const uint8_t nextWriteIndex
= (rxBufferWriteIndex
+ 1) % NUM_RX_BUFFERS
;
186 if (nextWriteIndex
!= rxBufferReadIndex
) {
187 rxBuffer
[rxBufferWriteIndex
].length
= framePosition
- 1;
188 rxBufferWriteIndex
= nextWriteIndex
;
191 if (telemetryFrame
) {
193 lastTelemetryFrameReceivedUs
= currentTimeUs
;
194 telemetryFrame
= false;
197 DEBUG_SET(DEBUG_FPORT
, DEBUG_FPORT_FRAME_INTERVAL
, currentTimeUs
- lastFrameReceivedUs
);
198 lastFrameReceivedUs
= currentTimeUs
;
200 escapedCharacter
= false;
203 frameStartAt
= currentTimeUs
;
206 rxBuffer
[rxBufferWriteIndex
].frameStartTimeUs
= currentTimeUs
;
207 } else if (framePosition
> 0) {
208 if (framePosition
>= BUFFER_SIZE
+ 1) {
211 reportFrameError(DEBUG_FPORT_ERROR_OVERSIZE
);
213 if (escapedCharacter
) {
214 val
= val
^ FPORT_ESCAPE_MASK
;
215 escapedCharacter
= false;
216 } else if (val
== FPORT_ESCAPE_CHAR
) {
217 escapedCharacter
= true;
222 if (framePosition
== 2 && val
== FPORT_FRAME_TYPE_TELEMETRY_REQUEST
) {
223 telemetryFrame
= true;
226 rxBuffer
[rxBufferWriteIndex
].data
[framePosition
- 1] = val
;
227 framePosition
= framePosition
+ 1;
232 #if defined(USE_TELEMETRY_SMARTPORT)
233 static void smartPortWriteFrameFport(const smartPortPayload_t
*payload
)
237 uint16_t checksum
= 0;
238 smartPortSendByte(FPORT_RESPONSE_FRAME_LENGTH
, &checksum
, fportPort
);
239 smartPortSendByte(FPORT_FRAME_TYPE_TELEMETRY_RESPONSE
, &checksum
, fportPort
);
240 smartPortWriteFrameSerial(payload
, fportPort
, checksum
);
244 static uint8_t fportFrameStatus(rxRuntimeState_t
*rxRuntimeState
)
246 static bool hasTelemetryRequest
= false;
248 #ifdef USE_TELEMETRY_SMARTPORT
249 static smartPortPayload_t payloadBuffer
;
250 static bool rxDrivenFrameRate
= false;
251 static uint8_t consecutiveTelemetryFrameCount
= 0;
254 uint8_t result
= RX_FRAME_PENDING
;
256 if (rxBufferReadIndex
!= rxBufferWriteIndex
) {
257 uint8_t bufferLength
= rxBuffer
[rxBufferReadIndex
].length
;
258 uint8_t frameLength
= rxBuffer
[rxBufferReadIndex
].data
[0];
259 if (frameLength
!= bufferLength
- 2) {
260 reportFrameError(DEBUG_FPORT_ERROR_SIZE
);
262 if (!frskyCheckSumIsGood(&rxBuffer
[rxBufferReadIndex
].data
[0], bufferLength
)) {
263 reportFrameError(DEBUG_FPORT_ERROR_CHECKSUM
);
265 fportFrame_t
*frame
= (fportFrame_t
*)&rxBuffer
[rxBufferReadIndex
].data
[1];
267 switch (frame
->type
) {
268 case FPORT_FRAME_TYPE_CONTROL
:
269 if (frameLength
!= FPORT_FRAME_PAYLOAD_LENGTH_CONTROL
) {
270 reportFrameError(DEBUG_FPORT_ERROR_TYPE_SIZE
);
272 result
= sbusChannelsDecode(rxRuntimeState
, &frame
->data
.controlData
.channels
);
274 setRssi(scaleRange(frame
->data
.controlData
.rssi
, 0, 100, 0, RSSI_MAX_VALUE
), RSSI_SOURCE_RX_PROTOCOL
);
276 lastRcFrameReceivedMs
= millis();
278 if (!(result
& (RX_FRAME_FAILSAFE
| RX_FRAME_DROPPED
))) {
279 rxRuntimeState
->lastRcFrameTimeUs
= rxBuffer
[rxBufferReadIndex
].frameStartTimeUs
;
284 case FPORT_FRAME_TYPE_TELEMETRY_REQUEST
:
285 if (frameLength
!= FPORT_FRAME_PAYLOAD_LENGTH_TELEMETRY_REQUEST
) {
286 reportFrameError(DEBUG_FPORT_ERROR_TYPE_SIZE
);
288 #if defined(USE_TELEMETRY_SMARTPORT)
289 if (!telemetryEnabled
) {
293 switch(frame
->data
.telemetryData
.frameId
) {
294 case FPORT_FRAME_ID_DATA
:
295 if (!rxDrivenFrameRate
) {
296 rxDrivenFrameRate
= true;
299 hasTelemetryRequest
= true;
302 case FPORT_FRAME_ID_NULL
:
303 if (!rxDrivenFrameRate
) {
304 if (consecutiveTelemetryFrameCount
>= FPORT_TELEMETRY_MAX_CONSECUTIVE_TELEMETRY_FRAMES
&& !(mspPayload
&& smartPortPayloadContainsMSP(mspPayload
))) {
305 consecutiveTelemetryFrameCount
= 0;
307 hasTelemetryRequest
= true;
309 consecutiveTelemetryFrameCount
++;
314 case FPORT_FRAME_ID_READ
:
315 case FPORT_FRAME_ID_WRITE
: // never used
316 memcpy(&payloadBuffer
, &frame
->data
.telemetryData
, sizeof(smartPortPayload_t
));
317 mspPayload
= &payloadBuffer
;
329 reportFrameError(DEBUG_FPORT_ERROR_TYPE
);
337 rxBufferReadIndex
= (rxBufferReadIndex
+ 1) % NUM_RX_BUFFERS
;
340 if ((mspPayload
|| hasTelemetryRequest
) && cmpTimeUs(micros(), lastTelemetryFrameReceivedUs
) >= FPORT_MIN_TELEMETRY_RESPONSE_DELAY_US
) {
341 hasTelemetryRequest
= false;
343 result
= (result
& ~RX_FRAME_PENDING
) | RX_FRAME_PROCESSING_REQUIRED
;
346 if (lastRcFrameReceivedMs
&& ((millis() - lastRcFrameReceivedMs
) > FPORT_MAX_TELEMETRY_AGE_MS
)) {
347 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL
);
348 lastRcFrameReceivedMs
= 0;
354 static bool fportProcessFrame(const rxRuntimeState_t
*rxRuntimeState
)
356 UNUSED(rxRuntimeState
);
358 #if defined(USE_TELEMETRY_SMARTPORT)
359 static timeUs_t lastTelemetryFrameSentUs
;
361 timeUs_t currentTimeUs
= micros();
362 if (cmpTimeUs(currentTimeUs
, lastTelemetryFrameReceivedUs
) > FPORT_MAX_TELEMETRY_RESPONSE_DELAY_US
) {
367 processSmartPortTelemetry(mspPayload
, &clearToSend
, NULL
);
370 smartPortWriteFrameFport(&emptySmartPortFrame
);
375 DEBUG_SET(DEBUG_FPORT
, DEBUG_FPORT_TELEMETRY_INTERVAL
, currentTimeUs
- lastTelemetryFrameSentUs
);
376 lastTelemetryFrameSentUs
= currentTimeUs
;
385 bool fportRxInit(const rxConfig_t
*rxConfig
, rxRuntimeState_t
*rxRuntimeState
)
387 static uint16_t sbusChannelData
[SBUS_MAX_CHANNEL
];
388 rxRuntimeState
->channelData
= sbusChannelData
;
389 sbusChannelsInit(rxConfig
, rxRuntimeState
);
391 rxRuntimeState
->channelCount
= SBUS_MAX_CHANNEL
;
392 rxRuntimeState
->rcFrameStatusFn
= fportFrameStatus
;
393 rxRuntimeState
->rcProcessFrameFn
= fportProcessFrame
;
395 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_RX_SERIAL
);
400 fportPort
= openSerialPort(portConfig
->identifier
,
406 FPORT_PORT_OPTIONS
| (rxConfig
->serialrx_inverted
? SERIAL_INVERTED
: 0) | (rxConfig
->halfDuplex
? SERIAL_BIDIR
: 0)
410 #if defined(USE_TELEMETRY_SMARTPORT)
411 telemetryEnabled
= initSmartPortTelemetryExternal(smartPortWriteFrameFport
);
414 if (rssiSource
== RSSI_SOURCE_NONE
) {
415 rssiSource
= RSSI_SOURCE_RX_PROTOCOL
;
419 return fportPort
!= NULL
;