If RSSI Channel is set to Disabled when using S.Bus then generate RSS… (#5090)
[betaflight.git] / src / main / msp / msp_serial.c
blob0ce3c92d87935a9015dad4bb4f55e2c25ed6ddcd
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
22 #include "platform.h"
24 #include "build/debug.h"
26 #include "common/streambuf.h"
27 #include "common/utils.h"
28 #include "common/crc.h"
30 #include "drivers/system.h"
32 #include "interface/msp.h"
33 #include "interface/cli.h"
35 #include "io/serial.h"
37 #include "msp/msp_serial.h"
39 static mspPort_t mspPorts[MAX_MSP_PORT_COUNT];
41 static void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort)
43 memset(mspPortToReset, 0, sizeof(mspPort_t));
45 mspPortToReset->port = serialPort;
48 void mspSerialAllocatePorts(void)
50 uint8_t portIndex = 0;
51 serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_MSP);
52 while (portConfig && portIndex < MAX_MSP_PORT_COUNT) {
53 mspPort_t *mspPort = &mspPorts[portIndex];
54 if (mspPort->port) {
55 portIndex++;
56 continue;
59 serialPort_t *serialPort = openSerialPort(portConfig->identifier, FUNCTION_MSP, NULL, NULL, baudRates[portConfig->msp_baudrateIndex], MODE_RXTX, SERIAL_NOT_INVERTED);
60 if (serialPort) {
61 resetMspPort(mspPort, serialPort);
62 portIndex++;
65 portConfig = findNextSerialPortConfig(FUNCTION_MSP);
69 void mspSerialReleasePortIfAllocated(serialPort_t *serialPort)
71 for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
72 mspPort_t *candidateMspPort = &mspPorts[portIndex];
73 if (candidateMspPort->port == serialPort) {
74 closeSerialPort(serialPort);
75 memset(candidateMspPort, 0, sizeof(mspPort_t));
80 static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c)
82 switch (mspPort->c_state) {
83 default:
84 case MSP_IDLE: // Waiting for '$' character
85 if (c == '$') {
86 mspPort->mspVersion = MSP_V1;
87 mspPort->c_state = MSP_HEADER_START;
89 else {
90 return false;
92 break;
94 case MSP_HEADER_START: // Waiting for 'M' (MSPv1 / MSPv2_over_v1) or 'X' (MSPv2 native)
95 switch (c) {
96 case 'M':
97 mspPort->c_state = MSP_HEADER_M;
98 break;
99 case 'X':
100 mspPort->c_state = MSP_HEADER_X;
101 break;
102 default:
103 mspPort->c_state = MSP_IDLE;
104 break;
106 break;
108 case MSP_HEADER_M: // Waiting for '<'
109 if (c == '<') {
110 mspPort->offset = 0;
111 mspPort->checksum1 = 0;
112 mspPort->checksum2 = 0;
113 mspPort->c_state = MSP_HEADER_V1;
115 else {
116 mspPort->c_state = MSP_IDLE;
118 break;
120 case MSP_HEADER_X:
121 if (c == '<') {
122 mspPort->offset = 0;
123 mspPort->checksum2 = 0;
124 mspPort->mspVersion = MSP_V2_NATIVE;
125 mspPort->c_state = MSP_HEADER_V2_NATIVE;
127 else {
128 mspPort->c_state = MSP_IDLE;
130 break;
132 case MSP_HEADER_V1: // Now receive v1 header (size/cmd), this is already checksummable
133 mspPort->inBuf[mspPort->offset++] = c;
134 mspPort->checksum1 ^= c;
135 if (mspPort->offset == sizeof(mspHeaderV1_t)) {
136 mspHeaderV1_t * hdr = (mspHeaderV1_t *)&mspPort->inBuf[0];
137 // Check incoming buffer size limit
138 if (hdr->size > MSP_PORT_INBUF_SIZE) {
139 mspPort->c_state = MSP_IDLE;
141 else if (hdr->cmd == MSP_V2_FRAME_ID) {
142 // MSPv1 payload must be big enough to hold V2 header + extra checksum
143 if (hdr->size >= sizeof(mspHeaderV2_t) + 1) {
144 mspPort->mspVersion = MSP_V2_OVER_V1;
145 mspPort->c_state = MSP_HEADER_V2_OVER_V1;
147 else {
148 mspPort->c_state = MSP_IDLE;
151 else {
152 mspPort->dataSize = hdr->size;
153 mspPort->cmdMSP = hdr->cmd;
154 mspPort->cmdFlags = 0;
155 mspPort->offset = 0; // re-use buffer
156 mspPort->c_state = mspPort->dataSize > 0 ? MSP_PAYLOAD_V1 : MSP_CHECKSUM_V1; // If no payload - jump to checksum byte
159 break;
161 case MSP_PAYLOAD_V1:
162 mspPort->inBuf[mspPort->offset++] = c;
163 mspPort->checksum1 ^= c;
164 if (mspPort->offset == mspPort->dataSize) {
165 mspPort->c_state = MSP_CHECKSUM_V1;
167 break;
169 case MSP_CHECKSUM_V1:
170 if (mspPort->checksum1 == c) {
171 mspPort->c_state = MSP_COMMAND_RECEIVED;
172 } else {
173 mspPort->c_state = MSP_IDLE;
175 break;
177 case MSP_HEADER_V2_OVER_V1: // V2 header is part of V1 payload - we need to calculate both checksums now
178 mspPort->inBuf[mspPort->offset++] = c;
179 mspPort->checksum1 ^= c;
180 mspPort->checksum2 = crc8_dvb_s2(mspPort->checksum2, c);
181 if (mspPort->offset == (sizeof(mspHeaderV2_t) + sizeof(mspHeaderV1_t))) {
182 mspHeaderV2_t * hdrv2 = (mspHeaderV2_t *)&mspPort->inBuf[sizeof(mspHeaderV1_t)];
183 mspPort->dataSize = hdrv2->size;
184 mspPort->cmdMSP = hdrv2->cmd;
185 mspPort->cmdFlags = hdrv2->flags;
186 mspPort->offset = 0; // re-use buffer
187 mspPort->c_state = mspPort->dataSize > 0 ? MSP_PAYLOAD_V2_OVER_V1 : MSP_CHECKSUM_V2_OVER_V1;
189 break;
191 case MSP_PAYLOAD_V2_OVER_V1:
192 mspPort->checksum2 = crc8_dvb_s2(mspPort->checksum2, c);
193 mspPort->checksum1 ^= c;
194 mspPort->inBuf[mspPort->offset++] = c;
196 if (mspPort->offset == mspPort->dataSize) {
197 mspPort->c_state = MSP_CHECKSUM_V2_OVER_V1;
199 break;
201 case MSP_CHECKSUM_V2_OVER_V1:
202 mspPort->checksum1 ^= c;
203 if (mspPort->checksum2 == c) {
204 mspPort->c_state = MSP_CHECKSUM_V1; // Checksum 2 correct - verify v1 checksum
205 } else {
206 mspPort->c_state = MSP_IDLE;
208 break;
210 case MSP_HEADER_V2_NATIVE:
211 mspPort->inBuf[mspPort->offset++] = c;
212 mspPort->checksum2 = crc8_dvb_s2(mspPort->checksum2, c);
213 if (mspPort->offset == sizeof(mspHeaderV2_t)) {
214 mspHeaderV2_t * hdrv2 = (mspHeaderV2_t *)&mspPort->inBuf[0];
215 mspPort->dataSize = hdrv2->size;
216 mspPort->cmdMSP = hdrv2->cmd;
217 mspPort->cmdFlags = hdrv2->flags;
218 mspPort->offset = 0; // re-use buffer
219 mspPort->c_state = mspPort->dataSize > 0 ? MSP_PAYLOAD_V2_NATIVE : MSP_CHECKSUM_V2_NATIVE;
221 break;
223 case MSP_PAYLOAD_V2_NATIVE:
224 mspPort->checksum2 = crc8_dvb_s2(mspPort->checksum2, c);
225 mspPort->inBuf[mspPort->offset++] = c;
227 if (mspPort->offset == mspPort->dataSize) {
228 mspPort->c_state = MSP_CHECKSUM_V2_NATIVE;
230 break;
232 case MSP_CHECKSUM_V2_NATIVE:
233 if (mspPort->checksum2 == c) {
234 mspPort->c_state = MSP_COMMAND_RECEIVED;
235 } else {
236 mspPort->c_state = MSP_IDLE;
238 break;
241 return true;
244 static uint8_t mspSerialChecksumBuf(uint8_t checksum, const uint8_t *data, int len)
246 while (len-- > 0) {
247 checksum ^= *data++;
249 return checksum;
252 #define JUMBO_FRAME_SIZE_LIMIT 255
253 static int mspSerialSendFrame(mspPort_t *msp, const uint8_t * hdr, int hdrLen, const uint8_t * data, int dataLen, const uint8_t * crc, int crcLen)
255 // We are allowed to send out the response if
256 // a) TX buffer is completely empty (we are talking to well-behaving party that follows request-response scheduling;
257 // this allows us to transmit jumbo frames bigger than TX buffer (serialWriteBuf will block, but for jumbo frames we don't care)
258 // b) Response fits into TX buffer
259 const int totalFrameLength = hdrLen + dataLen + crcLen;
260 if (!isSerialTransmitBufferEmpty(msp->port) && ((int)serialTxBytesFree(msp->port) < totalFrameLength))
261 return 0;
263 // Transmit frame
264 serialBeginWrite(msp->port);
265 serialWriteBuf(msp->port, hdr, hdrLen);
266 serialWriteBuf(msp->port, data, dataLen);
267 serialWriteBuf(msp->port, crc, crcLen);
268 serialEndWrite(msp->port);
270 return totalFrameLength;
273 static int mspSerialEncode(mspPort_t *msp, mspPacket_t *packet, mspVersion_e mspVersion)
275 static const uint8_t mspMagic[MSP_VERSION_COUNT] = MSP_VERSION_MAGIC_INITIALIZER;
276 const int dataLen = sbufBytesRemaining(&packet->buf);
277 uint8_t hdrBuf[16] = { '$', mspMagic[mspVersion], packet->result == MSP_RESULT_ERROR ? '!' : '>'};
278 uint8_t crcBuf[2];
279 uint8_t checksum;
280 int hdrLen = 3;
281 int crcLen = 0;
283 #define V1_CHECKSUM_STARTPOS 3
284 if (mspVersion == MSP_V1) {
285 mspHeaderV1_t * hdrV1 = (mspHeaderV1_t *)&hdrBuf[hdrLen];
286 hdrLen += sizeof(mspHeaderV1_t);
287 hdrV1->cmd = packet->cmd;
289 // Add JUMBO-frame header if necessary
290 if (dataLen >= JUMBO_FRAME_SIZE_LIMIT) {
291 mspHeaderJUMBO_t * hdrJUMBO = (mspHeaderJUMBO_t *)&hdrBuf[hdrLen];
292 hdrLen += sizeof(mspHeaderJUMBO_t);
294 hdrV1->size = JUMBO_FRAME_SIZE_LIMIT;
295 hdrJUMBO->size = dataLen;
297 else {
298 hdrV1->size = dataLen;
301 // Pre-calculate CRC
302 checksum = mspSerialChecksumBuf(0, hdrBuf + V1_CHECKSUM_STARTPOS, hdrLen - V1_CHECKSUM_STARTPOS);
303 checksum = mspSerialChecksumBuf(checksum, sbufPtr(&packet->buf), dataLen);
304 crcBuf[crcLen++] = checksum;
306 else if (mspVersion == MSP_V2_OVER_V1) {
307 mspHeaderV1_t * hdrV1 = (mspHeaderV1_t *)&hdrBuf[hdrLen];
309 hdrLen += sizeof(mspHeaderV1_t);
311 mspHeaderV2_t * hdrV2 = (mspHeaderV2_t *)&hdrBuf[hdrLen];
312 hdrLen += sizeof(mspHeaderV2_t);
314 const int v1PayloadSize = sizeof(mspHeaderV2_t) + dataLen + 1; // MSPv2 header + data payload + MSPv2 checksum
315 hdrV1->cmd = MSP_V2_FRAME_ID;
317 // Add JUMBO-frame header if necessary
318 if (v1PayloadSize >= JUMBO_FRAME_SIZE_LIMIT) {
319 mspHeaderJUMBO_t * hdrJUMBO = (mspHeaderJUMBO_t *)&hdrBuf[hdrLen];
320 hdrLen += sizeof(mspHeaderJUMBO_t);
322 hdrV1->size = JUMBO_FRAME_SIZE_LIMIT;
323 hdrJUMBO->size = v1PayloadSize;
325 else {
326 hdrV1->size = v1PayloadSize;
329 // Fill V2 header
330 hdrV2->flags = packet->flags;
331 hdrV2->cmd = packet->cmd;
332 hdrV2->size = dataLen;
334 // V2 CRC: only V2 header + data payload
335 checksum = crc8_dvb_s2_update(0, (uint8_t *)hdrV2, sizeof(mspHeaderV2_t));
336 checksum = crc8_dvb_s2_update(checksum, sbufPtr(&packet->buf), dataLen);
337 crcBuf[crcLen++] = checksum;
339 // V1 CRC: All headers + data payload + V2 CRC byte
340 checksum = mspSerialChecksumBuf(0, hdrBuf + V1_CHECKSUM_STARTPOS, hdrLen - V1_CHECKSUM_STARTPOS);
341 checksum = mspSerialChecksumBuf(checksum, sbufPtr(&packet->buf), dataLen);
342 checksum = mspSerialChecksumBuf(checksum, crcBuf, crcLen);
343 crcBuf[crcLen++] = checksum;
345 else if (mspVersion == MSP_V2_NATIVE) {
346 mspHeaderV2_t * hdrV2 = (mspHeaderV2_t *)&hdrBuf[hdrLen];
347 hdrLen += sizeof(mspHeaderV2_t);
349 hdrV2->flags = packet->flags;
350 hdrV2->cmd = packet->cmd;
351 hdrV2->size = dataLen;
353 checksum = crc8_dvb_s2_update(0, (uint8_t *)hdrV2, sizeof(mspHeaderV2_t));
354 checksum = crc8_dvb_s2_update(checksum, sbufPtr(&packet->buf), dataLen);
355 crcBuf[crcLen++] = checksum;
357 else {
358 // Shouldn't get here
359 return 0;
362 // Send the frame
363 return mspSerialSendFrame(msp, hdrBuf, hdrLen, sbufPtr(&packet->buf), dataLen, crcBuf, crcLen);
366 static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspProcessCommandFnPtr mspProcessCommandFn)
368 static uint8_t outBuf[MSP_PORT_OUTBUF_SIZE];
370 mspPacket_t reply = {
371 .buf = { .ptr = outBuf, .end = ARRAYEND(outBuf), },
372 .cmd = -1,
373 .flags = 0,
374 .result = 0,
375 .direction = MSP_DIRECTION_REPLY,
377 uint8_t *outBufHead = reply.buf.ptr;
379 mspPacket_t command = {
380 .buf = { .ptr = msp->inBuf, .end = msp->inBuf + msp->dataSize, },
381 .cmd = msp->cmdMSP,
382 .flags = msp->cmdFlags,
383 .result = 0,
384 .direction = MSP_DIRECTION_REQUEST,
387 mspPostProcessFnPtr mspPostProcessFn = NULL;
388 const mspResult_e status = mspProcessCommandFn(&command, &reply, &mspPostProcessFn);
390 if (status != MSP_RESULT_NO_REPLY) {
391 sbufSwitchToReader(&reply.buf, outBufHead); // change streambuf direction
392 mspSerialEncode(msp, &reply, msp->mspVersion);
395 return mspPostProcessFn;
398 static void mspEvaluateNonMspData(mspPort_t * mspPort, uint8_t receivedChar)
400 #ifdef USE_CLI
401 if (receivedChar == '#') {
402 mspPort->pendingRequest = MSP_PENDING_CLI;
403 return;
405 #endif
407 if (receivedChar == serialConfig()->reboot_character) {
408 mspPort->pendingRequest = MSP_PENDING_BOOTLOADER;
409 return;
413 static void mspProcessPendingRequest(mspPort_t * mspPort)
415 // If no request is pending or 100ms guard time has not elapsed - do nothing
416 if ((mspPort->pendingRequest == MSP_PENDING_NONE) || (millis() - mspPort->lastActivityMs < 100)) {
417 return;
420 switch(mspPort->pendingRequest) {
421 case MSP_PENDING_BOOTLOADER:
422 systemResetToBootloader();
423 break;
425 #ifdef USE_CLI
426 case MSP_PENDING_CLI:
427 cliEnter(mspPort->port);
428 break;
429 #endif
431 default:
432 break;
436 static void mspSerialProcessReceivedReply(mspPort_t *msp, mspProcessReplyFnPtr mspProcessReplyFn)
438 mspPacket_t reply = {
439 .buf = {
440 .ptr = msp->inBuf,
441 .end = msp->inBuf + msp->dataSize,
443 .cmd = msp->cmdMSP,
444 .result = 0,
447 mspProcessReplyFn(&reply);
449 msp->c_state = MSP_IDLE;
453 * Process MSP commands from serial ports configured as MSP ports.
455 * Called periodically by the scheduler.
457 void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn, mspProcessReplyFnPtr mspProcessReplyFn)
459 for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
460 mspPort_t * const mspPort = &mspPorts[portIndex];
461 if (!mspPort->port) {
462 continue;
465 mspPostProcessFnPtr mspPostProcessFn = NULL;
467 if (serialRxBytesWaiting(mspPort->port)) {
468 // There are bytes incoming - abort pending request
469 mspPort->lastActivityMs = millis();
470 mspPort->pendingRequest = MSP_PENDING_NONE;
472 while (serialRxBytesWaiting(mspPort->port)) {
473 const uint8_t c = serialRead(mspPort->port);
474 const bool consumed = mspSerialProcessReceivedData(mspPort, c);
476 if (!consumed && evaluateNonMspData == MSP_EVALUATE_NON_MSP_DATA) {
477 mspEvaluateNonMspData(mspPort, c);
480 if (mspPort->c_state == MSP_COMMAND_RECEIVED) {
481 if (mspPort->packetType == MSP_PACKET_COMMAND) {
482 mspPostProcessFn = mspSerialProcessReceivedCommand(mspPort, mspProcessCommandFn);
483 } else if (mspPort->packetType == MSP_PACKET_REPLY) {
484 mspSerialProcessReceivedReply(mspPort, mspProcessReplyFn);
487 mspPort->c_state = MSP_IDLE;
488 break; // process one command at a time so as not to block.
492 if (mspPostProcessFn) {
493 waitForSerialPortToFinishTransmitting(mspPort->port);
494 mspPostProcessFn(mspPort->port);
497 else {
498 mspProcessPendingRequest(mspPort);
503 bool mspSerialWaiting(void)
505 for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
506 mspPort_t * const mspPort = &mspPorts[portIndex];
507 if (!mspPort->port) {
508 continue;
511 if (serialRxBytesWaiting(mspPort->port)) {
512 return true;
515 return false;
518 void mspSerialInit(void)
520 memset(mspPorts, 0, sizeof(mspPorts));
521 mspSerialAllocatePorts();
524 int mspSerialPush(uint8_t cmd, uint8_t *data, int datalen, mspDirection_e direction)
526 int ret = 0;
528 for (int portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
529 mspPort_t * const mspPort = &mspPorts[portIndex];
530 if (!mspPort->port) {
531 continue;
534 // XXX Kludge!!! Avoid zombie VCP port (avoid VCP entirely for now)
535 if (mspPort->port->identifier == SERIAL_PORT_USB_VCP) {
536 continue;
539 mspPacket_t push = {
540 .buf = { .ptr = data, .end = data + datalen, },
541 .cmd = cmd,
542 .result = 0,
543 .direction = direction,
546 ret = mspSerialEncode(mspPort, &push, MSP_V1);
548 return ret; // return the number of bytes written
552 uint32_t mspSerialTxBytesFree(void)
554 uint32_t ret = UINT32_MAX;
556 for (int portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
557 mspPort_t * const mspPort = &mspPorts[portIndex];
558 if (!mspPort->port) {
559 continue;
562 // XXX Kludge!!! Avoid zombie VCP port (avoid VCP entirely for now)
563 if (mspPort->port->identifier == SERIAL_PORT_USB_VCP) {
564 continue;
567 const uint32_t bytesFree = serialTxBytesFree(mspPort->port);
568 if (bytesFree < ret) {
569 ret = bytesFree;
573 return ret;