FIX: Adding init for SPIDEV_0 (#14134)
[betaflight.git] / src / main / rx / fport.c
blob80b57e07dbf5aa1d3b37de0d3233b25577b11eb4
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/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <stdlib.h>
24 #include <string.h>
26 #include "platform.h"
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"
39 #ifdef USE_TELEMETRY
40 #include "telemetry/telemetry.h"
41 #include "telemetry/smartport.h"
42 #endif
44 #include "pg/rx.h"
46 #include "rx/frsky_crc.h"
47 #include "rx/rx.h"
48 #include "rx/sbus_channels.h"
49 #include "rx/fport.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)
67 enum {
68 DEBUG_FPORT_FRAME_INTERVAL = 0,
69 DEBUG_FPORT_FRAME_ERRORS,
70 DEBUG_FPORT_FRAME_LAST_ERROR,
71 DEBUG_FPORT_TELEMETRY_INTERVAL,
74 enum {
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,
84 enum {
85 FPORT_FRAME_TYPE_CONTROL = 0x00,
86 FPORT_FRAME_TYPE_TELEMETRY_REQUEST = 0x01,
87 FPORT_FRAME_TYPE_TELEMETRY_RESPONSE = 0x81,
91 enum {
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;
101 uint8_t rssi;
102 } fportControlData_t;
104 typedef union fportData_s {
105 fportControlData_t controlData;
106 smartPortPayload_t telemetryData;
107 } fportData_t;
109 typedef struct fportFrame_s {
110 uint8_t type;
111 fportData_t data;
112 } fportFrame_t;
114 #ifdef USE_TELEMETRY_SMARTPORT
115 static const smartPortPayload_t emptySmartPortFrame = { .frameId = 0, .valueId = 0, .data = 0 };
116 #endif
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];
129 uint8_t length;
130 timeUs_t frameStartTimeUs;
131 } fportBuffer_t;
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;
149 #endif
151 static void reportFrameError(uint8_t errorReason)
153 static volatile uint16_t frameErrors = 0;
155 frameErrors++;
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)
164 UNUSED(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();
173 clearToSend = false;
175 if (framePosition > 1 && cmpTimeUs(currentTimeUs, frameStartAt) > FPORT_TIME_NEEDED_PER_FRAME_US + 500) {
176 reportFrameError(DEBUG_FPORT_ERROR_TIMEOUT);
178 framePosition = 0;
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) {
192 clearToSend = true;
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;
204 framePosition = 1;
206 rxBuffer[rxBufferWriteIndex].frameStartTimeUs = currentTimeUs;
207 } else if (framePosition > 0) {
208 if (framePosition >= BUFFER_SIZE + 1) {
209 framePosition = 0;
211 reportFrameError(DEBUG_FPORT_ERROR_OVERSIZE);
212 } else {
213 if (escapedCharacter) {
214 val = val ^ FPORT_ESCAPE_MASK;
215 escapedCharacter = false;
216 } else if (val == FPORT_ESCAPE_CHAR) {
217 escapedCharacter = true;
219 return;
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)
235 framePosition = 0;
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);
242 #endif
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;
252 #endif
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);
261 } else {
262 if (!frskyCheckSumIsGood(&rxBuffer[rxBufferReadIndex].data[0], bufferLength)) {
263 reportFrameError(DEBUG_FPORT_ERROR_CHECKSUM);
264 } else {
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);
271 } else {
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;
283 break;
284 case FPORT_FRAME_TYPE_TELEMETRY_REQUEST:
285 if (frameLength != FPORT_FRAME_PAYLOAD_LENGTH_TELEMETRY_REQUEST) {
286 reportFrameError(DEBUG_FPORT_ERROR_TYPE_SIZE);
287 } else {
288 #if defined(USE_TELEMETRY_SMARTPORT)
289 if (!telemetryEnabled) {
290 break;
293 switch(frame->data.telemetryData.frameId) {
294 case FPORT_FRAME_ID_DATA:
295 if (!rxDrivenFrameRate) {
296 rxDrivenFrameRate = true;
299 hasTelemetryRequest = true;
301 break;
302 case FPORT_FRAME_ID_NULL:
303 if (!rxDrivenFrameRate) {
304 if (consecutiveTelemetryFrameCount >= FPORT_TELEMETRY_MAX_CONSECUTIVE_TELEMETRY_FRAMES && !(mspPayload && smartPortPayloadContainsMSP(mspPayload))) {
305 consecutiveTelemetryFrameCount = 0;
306 } else {
307 hasTelemetryRequest = true;
309 consecutiveTelemetryFrameCount++;
313 break;
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;
319 break;
320 default:
322 break;
324 #endif
327 break;
328 default:
329 reportFrameError(DEBUG_FPORT_ERROR_TYPE);
331 break;
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;
351 return result;
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) {
363 clearToSend = false;
366 if (clearToSend) {
367 processSmartPortTelemetry(mspPayload, &clearToSend, NULL);
369 if (clearToSend) {
370 smartPortWriteFrameFport(&emptySmartPortFrame);
372 clearToSend = false;
375 DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT_TELEMETRY_INTERVAL, currentTimeUs - lastTelemetryFrameSentUs);
376 lastTelemetryFrameSentUs = currentTimeUs;
379 mspPayload = NULL;
380 #endif
382 return true;
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);
396 if (!portConfig) {
397 return false;
400 fportPort = openSerialPort(portConfig->identifier,
401 FUNCTION_RX_SERIAL,
402 fportDataReceive,
403 NULL,
404 FPORT_BAUDRATE,
405 MODE_RXTX,
406 FPORT_PORT_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0)
409 if (fportPort) {
410 #if defined(USE_TELEMETRY_SMARTPORT)
411 telemetryEnabled = initSmartPortTelemetryExternal(smartPortWriteFrameFport);
412 #endif
414 if (rssiSource == RSSI_SOURCE_NONE) {
415 rssiSource = RSSI_SOURCE_RX_PROTOCOL;
419 return fportPort != NULL;
421 #endif