Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / io / vtx_tramp.c
blob562eb30319a024bb0f727a8fd762e99fed3d4f3f
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 /* Created by jflyper */
23 #include <stdbool.h>
24 #include <stdint.h>
25 #include <ctype.h>
26 #include <string.h>
28 #include "platform.h"
30 #if defined(USE_VTX_TRAMP) && defined(USE_VTX_CONTROL)
32 #include "build/debug.h"
34 #include "common/maths.h"
35 #include "common/utils.h"
37 #include "cms/cms_menu_vtx_tramp.h"
39 #include "drivers/vtx_common.h"
40 #include "drivers/vtx_table.h"
42 #include "io/serial.h"
43 #include "io/vtx_tramp.h"
44 #include "io/vtx_control.h"
45 #include "io/vtx.h"
47 // Maximum number of requests sent to try a config change
48 // Some VTX fail to respond to every request (like Matek FCHUB-VTX) so
49 // we sometimes need multiple retries to get the VTX to respond.
50 #define TRAMP_MAX_RETRIES (20)
52 // Race lock - settings can't be changed
53 #define TRAMP_CONTROL_RACE_LOCK (0x01)
55 // Define periods between requests
56 #define TRAMP_MIN_REQUEST_PERIOD_US (200 * 1000) // 200ms
57 #define TRAMP_STATUS_REQUEST_PERIOD_US (1000 * 1000) // 1s
59 #if (defined(USE_CMS) || defined(USE_VTX_COMMON)) && !defined(USE_VTX_TABLE)
60 const uint16_t trampPowerTable[VTX_TRAMP_POWER_COUNT] = {
61 25, 100, 200, 400, 600
64 const char *trampPowerNames[VTX_TRAMP_POWER_COUNT + 1] = {
65 "---", "25 ", "100", "200", "400", "600"
67 #endif
69 #if defined(USE_VTX_COMMON)
70 static const vtxVTable_t trampVTable; // forward
71 static vtxDevice_t vtxTramp = {
72 .vTable = &trampVTable,
74 #endif
76 // Device serial port instance
77 static serialPort_t *trampSerialPort = NULL;
79 // Serial transmit and receive buffers
80 static uint8_t trampReqBuffer[16];
81 static uint8_t trampRespBuffer[16];
83 // Module state machine
84 typedef enum {
85 // Offline - device hasn't responded yet
86 TRAMP_STATUS_OFFLINE = 0,
87 // Init - fetching current settings from device
88 TRAMP_STATUS_INIT,
89 // Online - device is ready and being monitored - freq/power/pitmode
90 TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT,
91 // Online - device is ready and being monitored - temperature
92 TRAMP_STATUS_ONLINE_MONITOR_TEMP,
93 // Online - device is ready and config has just been updated
94 TRAMP_STATUS_ONLINE_CONFIG
95 } trampStatus_e;
97 // Module state
98 static trampStatus_e trampStatus = TRAMP_STATUS_OFFLINE;
100 // Device limits, read from device during init
101 static uint32_t trampRFFreqMin = 0;
102 static uint32_t trampRFFreqMax = 0;
103 static uint32_t trampRFPowerMax;
105 // Device status, read from device periodically
106 static uint32_t trampCurFreq = 0;
107 static uint16_t trampCurConfPower = 0; // Configured power
108 static uint16_t trampCurActPower = 0; // Actual power
109 static uint8_t trampCurPitMode = 0; // Expect to startup out of pitmode
110 static int16_t trampCurTemp = 0;
111 static uint8_t trampCurControlMode = 0;
113 // Device configuration, desired state of device
114 static uint32_t trampConfFreq = 0;
115 static uint16_t trampConfPower = 0;
116 static uint8_t trampConfPitMode = 0; // Initially configured out of pitmode
118 // Last device configuration, last desired state of device - used to reset
119 // retry count
120 static uint32_t trampLastConfFreq = 0;
121 static uint16_t trampLastConfPower = 0;
122 static uint8_t trampLastConfPitMode = 0; // Mirror trampConfPitMode
124 // Retry count
125 static uint8_t trampRetryCount = TRAMP_MAX_RETRIES;
127 // Receive state machine
128 typedef enum {
129 S_WAIT_LEN = 0, // Waiting for a packet len
130 S_WAIT_CODE, // Waiting for a response code
131 S_DATA, // Waiting for rest of the packet.
132 } trampReceiveState_e;
134 static trampReceiveState_e trampReceiveState = S_WAIT_LEN;
136 // Receive buffer index
137 static int trampReceivePos = 0;
139 // Last action time
140 static timeUs_t trampLastTimeUs = 0;
142 // Calculate tramp protocol checksum of provided buffer
143 static uint8_t trampChecksum(uint8_t *trampBuf)
145 uint8_t cksum = 0;
147 for (int i = 1 ; i < 14 ; i++) {
148 cksum += trampBuf[i];
151 return cksum;
154 // Check if race lock is enabled
155 static bool trampVtxRaceLockEnabled(void)
157 return trampCurControlMode & TRAMP_CONTROL_RACE_LOCK;
160 // Send tramp protocol frame to device
161 static void trampSendU16(uint8_t cmd, uint16_t param)
163 if (!trampSerialPort) {
164 return;
167 memset(trampReqBuffer, 0, ARRAYLEN(trampReqBuffer));
168 trampReqBuffer[0] = 0x0F;
169 trampReqBuffer[1] = cmd;
170 trampReqBuffer[2] = param & 0xff;
171 trampReqBuffer[3] = (param >> 8) & 0xff;
172 trampReqBuffer[14] = trampChecksum(trampReqBuffer);
173 serialWriteBuf(trampSerialPort, trampReqBuffer, 16);
176 // Send command to device
177 static void trampSendCommand(uint8_t cmd, uint16_t param)
179 // Is VTX control enabled?
180 if (!IS_RC_MODE_ACTIVE(BOXVTXCONTROLDISABLE)) {
181 // Yes, send command
182 trampSendU16(cmd, param);
186 // Process response and return code if valid else 0
187 static char trampHandleResponse(void)
189 const uint8_t respCode = trampRespBuffer[1];
191 switch (respCode) {
192 case 'r':
194 const uint16_t min_freq = trampRespBuffer[2]|(trampRespBuffer[3] << 8);
195 // Check we're not reading the request (indicated by freq zero)
196 if (min_freq != 0) {
197 // Got response, update device limits
198 trampRFFreqMin = min_freq;
199 trampRFFreqMax = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
200 trampRFPowerMax = trampRespBuffer[6]|(trampRespBuffer[7] << 8);
201 return 'r';
203 break;
205 case 'v':
207 const uint16_t freq = trampRespBuffer[2]|(trampRespBuffer[3] << 8);
208 // Check we're not reading the request (indicated by freq zero)
209 if (freq != 0) {
210 // Got response, update device status
211 trampCurFreq = freq;
212 trampCurConfPower = trampRespBuffer[4]|(trampRespBuffer[5] << 8);
213 trampCurControlMode = trampRespBuffer[6]; // Currently only used for race lock
214 trampCurPitMode = trampRespBuffer[7];
215 trampCurActPower = trampRespBuffer[8]|(trampRespBuffer[9] << 8);
217 // Init config with current status if not set
218 if (trampConfFreq == 0) {
219 trampConfFreq = trampCurFreq;
221 if (trampConfPower == 0) {
222 trampConfPower = trampCurConfPower;
224 return 'v';
226 break;
228 case 's':
230 const uint16_t temp = (int16_t)(trampRespBuffer[6]|(trampRespBuffer[7] << 8));
231 // Check we're not reading the request (indicated by temp zero)
232 if (temp != 0) {
233 // Got response, update device status
234 trampCurTemp = temp;
235 return 's';
237 break;
241 // Likely reading a request, return zero to indicate not accepted
242 return 0;
245 // Reset receiver state machine
246 static void trampResetReceiver(void)
248 trampReceiveState = S_WAIT_LEN;
249 trampReceivePos = 0;
252 // returns completed response code or 0
253 static char trampReceive()
255 if (!trampSerialPort) {
256 return 0;
259 while (serialRxBytesWaiting(trampSerialPort)) {
260 const uint8_t c = serialRead(trampSerialPort);
261 trampRespBuffer[trampReceivePos++] = c;
263 switch (trampReceiveState) {
264 case S_WAIT_LEN:
266 if (c == 0x0F) {
267 // Found header byte, advance to wait for code
268 trampReceiveState = S_WAIT_CODE;
269 } else {
270 // Unexpected header, reset state machine
271 trampResetReceiver();
273 break;
275 case S_WAIT_CODE:
277 if (c == 'r' || c == 'v' || c == 's') {
278 // Code is for response is one we're interested in, advance to data
279 trampReceiveState = S_DATA;
280 } else {
281 // Unexpected code, reset state machine
282 trampResetReceiver();
284 break;
286 case S_DATA:
288 if (trampReceivePos == 16) {
289 // Buffer is full, calculate checksum
290 uint8_t cksum = trampChecksum(trampRespBuffer);
292 // Reset state machine ready for next response
293 trampResetReceiver();
295 if ((trampRespBuffer[14] == cksum) && (trampRespBuffer[15] == 0)) {
296 // Checksum is correct, process response
297 char r = trampHandleResponse();
299 // Check response valid else keep on reading
300 if (r != 0) {
301 return r;
305 break;
307 default:
309 // Invalid state, reset state machine
310 trampResetReceiver();
311 break;
316 return 0;
319 static void trampQuery(uint8_t cmd)
321 // Reset receive buffer and issue command
322 trampResetReceiver();
323 trampSendU16(cmd, 0);
326 static void vtxTrampProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
328 UNUSED(vtxDevice);
329 bool configUpdateRequired = false;
331 // Read response from device
332 const char replyCode = trampReceive();
334 // Act on state
335 switch(trampStatus) {
336 case TRAMP_STATUS_OFFLINE:
338 // Offline, check for response
339 if (replyCode == 'r') {
340 // Device replied to reset? request, enter init
341 trampStatus = TRAMP_STATUS_INIT;
342 } else if (cmp32(currentTimeUs, trampLastTimeUs) >= TRAMP_MIN_REQUEST_PERIOD_US) {
343 // Min request period exceeded, issue another reset?
344 trampQuery('r');
346 // Update last time
347 trampLastTimeUs = currentTimeUs;
349 break;
351 case TRAMP_STATUS_INIT:
353 // Initializing, check for response
354 if (replyCode == 'v') {
355 // Device replied to freq / power / pit query, enter online
356 trampStatus = TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT;
357 } else if (cmp32(currentTimeUs, trampLastTimeUs) >= TRAMP_MIN_REQUEST_PERIOD_US) {
358 // Min request period exceeded, issue another query
359 trampQuery('v');
361 // Update last time
362 trampLastTimeUs = currentTimeUs;
364 break;
366 case TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT:
368 // Note after config a status update request is made, a new status
369 // request is made, this request is handled above and should prevent
370 // subsiquent config updates if the config is now correct
371 if (trampRetryCount > 0 && (cmp32(currentTimeUs, trampLastTimeUs) >= TRAMP_MIN_REQUEST_PERIOD_US)) {
372 // Config retries remain and min request period exceeded, check freq
373 if (!trampVtxRaceLockEnabled() && (trampConfFreq != trampCurFreq)) {
374 // Freq can be and needs to be updated, issue request
375 trampSendCommand('F', trampConfFreq);
377 // Set flag
378 configUpdateRequired = true;
379 } else if (!trampVtxRaceLockEnabled() && (trampConfPower != trampCurConfPower)) {
380 // Power can be and needs to be updated, issue request
381 trampSendCommand('P', trampConfPower);
383 // Set flag
384 configUpdateRequired = true;
385 } else if (trampConfPitMode != trampCurPitMode) {
386 // Pit mode needs to be updated, issue request
387 trampSendCommand('I', trampConfPitMode ? 0 : 1);
389 // Set flag
390 configUpdateRequired = true;
393 if (configUpdateRequired) {
394 // Update required, decrement retry count
395 trampRetryCount--;
397 // Update last time
398 trampLastTimeUs = currentTimeUs;
400 // Advance state
401 trampStatus = TRAMP_STATUS_ONLINE_CONFIG;
402 } else {
403 // No update required, reset retry count
404 trampRetryCount = TRAMP_MAX_RETRIES;
408 /* Was a config update made? */
409 if (!configUpdateRequired) {
410 /* No, look to continue monitoring */
411 if (cmp32(currentTimeUs, trampLastTimeUs) >= TRAMP_STATUS_REQUEST_PERIOD_US) {
412 // Request period exceeded, issue freq/power/pit query
413 trampQuery('v');
415 // Update last time
416 trampLastTimeUs = currentTimeUs;
417 } else if (replyCode == 'v') {
418 // Got reply, issue temp query
419 trampQuery('s');
421 // Wait for reply
422 trampStatus = TRAMP_STATUS_ONLINE_MONITOR_TEMP;
424 // Update last time
425 trampLastTimeUs = currentTimeUs;
429 break;
431 case TRAMP_STATUS_ONLINE_MONITOR_TEMP:
433 // Check request time
434 if (replyCode == 's') {
435 // Got reply, return to request freq/power/pit
436 trampStatus = TRAMP_STATUS_ONLINE_MONITOR_TEMP;
437 } else if (cmp32(currentTimeUs, trampLastTimeUs) >= TRAMP_MIN_REQUEST_PERIOD_US) {
438 // Timed out after min request period, return to request freq/power/pit query
439 trampStatus = TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT;
441 break;
443 case TRAMP_STATUS_ONLINE_CONFIG:
445 // Param should now be set, check time
446 if (cmp32(currentTimeUs, trampLastTimeUs) >= TRAMP_MIN_REQUEST_PERIOD_US) {
447 // Min request period exceeded, re-query
448 trampQuery('v');
450 // Advance state
451 trampStatus = TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT;
453 // Update last time
454 trampLastTimeUs = currentTimeUs;
456 break;
458 default:
460 // Invalid state, reset
461 trampStatus = TRAMP_STATUS_OFFLINE;
462 break;
466 DEBUG_SET(DEBUG_VTX_TRAMP, 0, trampStatus);
467 DEBUG_SET(DEBUG_VTX_TRAMP, 1, replyCode);
468 DEBUG_SET(DEBUG_VTX_TRAMP, 2, ((trampConfPitMode << 14) & 0xC000) |
469 ((trampCurPitMode << 12) & 0x3000) |
470 ((trampConfPower << 8) & 0x0F00) |
471 ((trampCurConfPower << 4) & 0x00F0) |
472 ((trampConfFreq != trampCurFreq) ? 0x0008 : 0x0000) |
473 ((trampConfPower != trampCurConfPower) ? 0x0004 : 0x0000) |
474 ((trampConfPitMode != trampCurPitMode) ? 0x0002 : 0x0000) |
475 (configUpdateRequired ? 0x0001 : 0x0000));
476 DEBUG_SET(DEBUG_VTX_TRAMP, 3, trampRetryCount);
478 #ifdef USE_CMS
479 trampCmsUpdateStatusString();
480 #endif
483 #ifdef USE_VTX_COMMON
485 // Interface to common VTX API
487 static vtxDevType_e vtxTrampGetDeviceType(const vtxDevice_t *vtxDevice)
489 UNUSED(vtxDevice);
490 return VTXDEV_TRAMP;
493 static bool vtxTrampIsReady(const vtxDevice_t *vtxDevice)
495 return vtxDevice != NULL && trampStatus >= TRAMP_STATUS_ONLINE_MONITOR_FREQPWRPIT;
498 static void vtxTrampSetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
500 UNUSED(vtxDevice);
501 UNUSED(band);
502 UNUSED(channel);
503 //tramp does not support band/channel mode, only frequency
506 static void vtxTrampSetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
508 uint16_t powerValue;
510 // Lookup power level value
511 if (vtxCommonLookupPowerValue(vtxDevice, index, &powerValue)) {
512 // Value found, apply
513 trampConfPower = powerValue;
514 if (trampConfPower != trampLastConfPower) {
515 // Requested power changed, reset retry count
516 trampRetryCount = TRAMP_MAX_RETRIES;
517 trampLastConfPower = trampConfPower;
522 static void vtxTrampSetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
524 UNUSED(vtxDevice);
526 trampConfPitMode = onoff;
527 if (trampConfPitMode != trampLastConfPitMode) {
528 // Requested pitmode changed, reset retry count
529 trampRetryCount = TRAMP_MAX_RETRIES;
530 trampLastConfPitMode = trampConfPitMode;
534 static void vtxTrampSetFreq(vtxDevice_t *vtxDevice, uint16_t freq)
536 UNUSED(vtxDevice);
538 uint8_t freqValid;
540 // Check frequency valid
541 if (trampRFFreqMin != 0 && trampRFFreqMax != 0) {
542 freqValid = (freq >= trampRFFreqMin && freq <= trampRFFreqMax);
543 } else {
544 freqValid = (freq >= VTX_TRAMP_MIN_FREQUENCY_MHZ && freq <= VTX_TRAMP_MAX_FREQUENCY_MHZ);
547 // Is frequency valid?
548 if (freqValid) {
549 // Yes, set freq
550 trampConfFreq = freq;
551 if (trampConfFreq != trampLastConfFreq) {
552 // Requested freq changed, reset retry count
553 trampRetryCount = TRAMP_MAX_RETRIES;
554 trampLastConfFreq = trampConfFreq;
559 static bool vtxTrampGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
561 if (!vtxTrampIsReady(vtxDevice)) {
562 return false;
565 // tramp does not support band and channel
566 *pBand = 0;
567 *pChannel = 0;
568 return true;
571 static bool vtxTrampGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
573 if (!vtxTrampIsReady(vtxDevice)) {
574 return false;
577 // Special case, power not set
578 if (trampConfPower == 0) {
579 *pIndex = 0;
580 return true;
583 // Lookup value in table
584 for (uint8_t i = 0; i < vtxTablePowerLevels; i++) {
585 // Find value that matches current configured power level
586 if (trampConfPower == vtxTablePowerValues[i]) {
587 // Value found, return index
588 *pIndex = i + 1;
589 return true;
593 // Value not found in table
594 return false;
597 static bool vtxTrampGetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
599 if (!vtxTrampIsReady(vtxDevice)) {
600 return false;
603 *pFreq = trampCurFreq;
604 return true;
607 static bool vtxTrampGetStatus(const vtxDevice_t *vtxDevice, unsigned *status)
609 if (!vtxTrampIsReady(vtxDevice)) {
610 return false;
613 // Mirror configued pit mode state rather than use current pitmode as we
614 // should, otherwise the logic in vtxProcessPitMode may not get us to the
615 // correct state if pitmode is toggled quickly
616 *status = (trampConfPitMode ? VTX_STATUS_PIT_MODE : 0);
618 // Check VTX is not locked
619 *status |= ((trampCurControlMode & TRAMP_CONTROL_RACE_LOCK) ? VTX_STATUS_LOCKED : 0);
621 return true;
624 static uint8_t vtxTrampGetPowerLevels(const vtxDevice_t *vtxDevice, uint16_t *levels, uint16_t *powers)
626 UNUSED(vtxDevice);
627 UNUSED(levels);
628 UNUSED(powers);
630 return 0;
633 static const vtxVTable_t trampVTable = {
634 .process = vtxTrampProcess,
635 .getDeviceType = vtxTrampGetDeviceType,
636 .isReady = vtxTrampIsReady,
637 .setBandAndChannel = vtxTrampSetBandAndChannel,
638 .setPowerByIndex = vtxTrampSetPowerByIndex,
639 .setPitMode = vtxTrampSetPitMode,
640 .setFrequency = vtxTrampSetFreq,
641 .getBandAndChannel = vtxTrampGetBandAndChannel,
642 .getPowerIndex = vtxTrampGetPowerIndex,
643 .getFrequency = vtxTrampGetFreq,
644 .getStatus = vtxTrampGetStatus,
645 .getPowerLevels = vtxTrampGetPowerLevels,
646 .serializeCustomDeviceStatus = NULL,
648 #endif
650 bool vtxTrampInit(void)
652 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_TRAMP);
654 if (portConfig) {
655 portOptions_e portOptions = 0;
656 #if defined(USE_VTX_COMMON)
657 portOptions = portOptions | (vtxConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR);
658 #else
659 portOptions = SERIAL_BIDIR;
660 #endif
662 trampSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_TRAMP, NULL, NULL, 9600, MODE_RXTX, portOptions);
665 if (!trampSerialPort) {
666 return false;
669 // XXX Effect of USE_VTX_COMMON should be reviewed, as following call to vtxInit will do nothing if vtxCommonSetDevice is not called.
670 #if defined(USE_VTX_COMMON)
672 vtxCommonSetDevice(&vtxTramp);
673 #ifndef USE_VTX_TABLE
674 //without USE_VTX_TABLE, fill vtxTable variables with default settings (instead of loading them from PG)
675 vtxTablePowerLevels = VTX_TRAMP_POWER_COUNT;
676 for (int i = 0; i < VTX_TRAMP_POWER_COUNT + 1; i++) {
677 vtxTablePowerLabels[i] = trampPowerNames[i];
679 for (int i = 0; i < VTX_TRAMP_POWER_COUNT; i++) {
680 vtxTablePowerValues[i] = trampPowerTable[i];
682 #endif
684 #endif
686 vtxInit();
688 return true;
691 uint16_t vtxTrampGetCurrentActualPower()
693 return trampCurActPower;
696 uint16_t vtxTrampGetCurrentTemp()
698 return trampCurTemp;
701 #endif // VTX_TRAMP