Merge pull request #11297 from SteveCEvans/baro_state
[betaflight.git] / src / main / io / vtx_smartaudio.c
blobf65d91d0759e82d7a609ad21b015777fdba47315
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 <string.h>
26 #include <math.h>
27 #include <ctype.h>
29 #include "platform.h"
31 #if defined(USE_VTX_SMARTAUDIO) && defined(USE_VTX_CONTROL)
33 #include "build/debug.h"
35 #include "cms/cms.h"
36 #include "cms/cms_menu_vtx_smartaudio.h"
38 #include "common/maths.h"
39 #include "common/printf.h"
40 #include "common/utils.h"
42 #include "drivers/time.h"
43 #include "drivers/vtx_common.h"
44 #include "drivers/vtx_table.h"
46 #include "io/serial.h"
47 #include "io/vtx.h"
48 #include "io/vtx_control.h"
49 #include "io/vtx_smartaudio.h"
52 // Timing parameters
53 // Note that vtxSAProcess() is normally called at 200ms interval
54 #define SMARTAUDIO_CMD_TIMEOUT 120 // Time until the command is considered lost
55 #define SMARTAUDIO_POLLING_INTERVAL 150 // Minimum time between state polling
56 #define SMARTAUDIO_POLLING_WINDOW 1000 // Time window after command polling for state change
58 #ifdef USE_SMARTAUDIO_DPRINTF
59 serialPort_t *debugSerialPort = NULL;
60 #endif // USE_SMARTAUDIO_DPRINTF
62 static serialPort_t *smartAudioSerialPort = NULL;
64 smartAudioDevice_t saDevice;
66 #ifdef USE_VTX_COMMON
67 static const vtxVTable_t saVTable; // Forward
68 static vtxDevice_t vtxSmartAudio = {
69 .vTable = &saVTable,
71 #endif
73 // SmartAudio command and response codes
74 enum {
75 SA_CMD_NONE = 0x00,
76 SA_CMD_GET_SETTINGS = 0x01,
77 SA_CMD_SET_POWER,
78 SA_CMD_SET_CHAN,
79 SA_CMD_SET_FREQ,
80 SA_CMD_SET_MODE,
81 SA_CMD_GET_SETTINGS_V2 = 0x09, // Response only
82 SA_CMD_GET_SETTINGS_V21 = 0x11,
83 } smartAudioCommand_e;
85 // This is not a good design; can't distinguish command from response this way.
86 #define SACMD(cmd) (((cmd) << 1) | 1)
89 #define SA_IS_PITMODE(n) ((n) & SA_MODE_GET_PITMODE)
90 #define SA_IS_PIRMODE(n) (((n) & SA_MODE_GET_PITMODE) && ((n) & SA_MODE_GET_IN_RANGE_PITMODE))
91 #define SA_IS_PORMODE(n) (((n) & SA_MODE_GET_PITMODE) && ((n) & SA_MODE_GET_OUT_RANGE_PITMODE))
94 // convert between 'saDevice.channel' and band/channel values
95 #define SA_DEVICE_CHVAL_TO_BAND(val) ((val) / (uint8_t)vtxTableChannelCount) + 1
96 #define SA_DEVICE_CHVAL_TO_CHANNEL(val) ((val) % (uint8_t)vtxTableChannelCount) + 1
97 #define SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel) ((band - 1) * (uint8_t)vtxTableChannelCount + (channel - 1))
100 // Statistical counters, for user side trouble shooting.
102 smartAudioStat_t saStat = {
103 .pktsent = 0,
104 .pktrcvd = 0,
105 .badpre = 0,
106 .badlen = 0,
107 .crc = 0,
108 .ooopresp = 0,
109 .badcode = 0,
112 // Last received device ('hard') states
114 smartAudioDevice_t saDevice = {
115 .version = 0,
116 .channel = -1,
117 .power = 0,
118 .mode = 0,
119 .freq = 0,
120 .orfreq = 0,
121 .willBootIntoPitMode = false,
124 static smartAudioDevice_t saDevicePrev = {
125 .version = 0,
128 // XXX Possible compliance problem here. Need LOCK/UNLOCK menu?
129 static uint8_t saLockMode = SA_MODE_SET_UNLOCK; // saCms variable?
131 #ifdef USE_VTX_TABLE
132 #define VTX_SMARTAUDIO_POWER_COUNT VTX_TABLE_MAX_POWER_LEVELS
133 #else // USE_VTX_TABLE
134 #define VTX_SMARTAUDIO_POWER_COUNT 4
135 static char saSupportedPowerLabels[VTX_SMARTAUDIO_POWER_COUNT + 1][4] = {"---", "25 ", "200", "500", "800"};
136 static char *saSupportedPowerLabelPointerArray[VTX_SMARTAUDIO_POWER_COUNT + 1];
137 #endif // USE_VTX_TABLE
138 static uint8_t saSupportedNumPowerLevels = VTX_SMARTAUDIO_POWER_COUNT;
139 static uint16_t saSupportedPowerValues[VTX_SMARTAUDIO_POWER_COUNT];
141 // XXX Should be configurable by user?
142 bool saDeferred = true; // saCms variable?
144 // Receive frame reassembly buffer
145 #define SA_MAX_RCVLEN 21
146 static uint8_t sa_rbuf[SA_MAX_RCVLEN + 4]; // XXX delete 4 byte guard
149 // CRC8 computations
152 #define POLYGEN 0xd5
154 static uint8_t CRC8(const uint8_t *data, const int8_t len)
156 uint8_t crc = 0; /* start with 0 so first byte can be 'xored' in */
157 uint8_t currByte;
159 for (int i = 0 ; i < len ; i++) {
160 currByte = data[i];
162 crc ^= currByte; /* XOR-in the next input byte */
164 for (int i = 0; i < 8; i++) {
165 if ((crc & 0x80) != 0) {
166 crc = (uint8_t)((crc << 1) ^ POLYGEN);
167 } else {
168 crc <<= 1;
172 return crc;
176 #ifdef USE_SMARTAUDIO_DPRINTF
177 static void saPrintSettings(void)
179 dprintf(("Current status: version: %d\r\n", saDevice.version));
180 dprintf((" mode(0x%x): fmode=%s", saDevice.mode, (saDevice.mode & 1) ? "freq" : "chan"));
181 dprintf((" pit=%s ", (saDevice.mode & 2) ? "on " : "off"));
182 dprintf((" inb=%s", (saDevice.mode & 4) ? "on " : "off"));
183 dprintf((" outb=%s", (saDevice.mode & 8) ? "on " : "off"));
184 dprintf((" lock=%s", (saDevice.mode & 16) ? "unlocked" : "locked"));
185 dprintf((" deferred=%s\r\n", (saDevice.mode & 32) ? "on" : "off"));
186 dprintf((" channel: %d ", saDevice.channel));
187 dprintf(("freq: %d ", saDevice.freq));
188 dprintf(("power: %d ", saDevice.power));
189 dprintf(("powerval: %d ", saDevice.power > 0 ? vtxTablePowerValues[saDevice.power - 1] : -1));
190 dprintf(("pitfreq: %d ", saDevice.orfreq));
191 dprintf(("BootIntoPitMode: %s ", saDevice.willBootIntoPitMode ? "yes" : "no"));
192 dprintf(("\r\n"));
194 #endif
197 // Autobauding
200 #define SMARTBAUD_MIN 4800
201 #define SMARTBAUD_MAX 4950
202 uint16_t sa_smartbaud = SMARTBAUD_MIN;
203 static int sa_adjdir = 1; // -1=going down, 1=going up
204 static int sa_baudstep = 50;
206 static void saAutobaud(void)
208 if (saStat.pktsent < 10) {
209 // Not enough samples collected
210 return;
213 #if 0
214 dprintf(("autobaud: %d rcvd %d/%d (%d)\r\n",
215 sa_smartbaud, saStat.pktrcvd, saStat.pktsent, ((saStat.pktrcvd * 100) / saStat.pktsent)));
216 #endif
218 if (((saStat.pktrcvd * 100) / saStat.pktsent) >= 70) {
219 // This is okay
220 saStat.pktsent = 0; // Should be more moderate?
221 saStat.pktrcvd = 0;
222 return;
225 dprintf(("autobaud: adjusting\r\n"));
227 if ((sa_adjdir == 1) && (sa_smartbaud == SMARTBAUD_MAX)) {
228 sa_adjdir = -1;
229 dprintf(("autobaud: now going down\r\n"));
230 } else if ((sa_adjdir == -1 && sa_smartbaud == SMARTBAUD_MIN)) {
231 sa_adjdir = 1;
232 dprintf(("autobaud: now going up\r\n"));
235 sa_smartbaud += sa_baudstep * sa_adjdir;
237 dprintf(("autobaud: %d\r\n", sa_smartbaud));
239 smartAudioSerialPort->vTable->serialSetBaudRate(smartAudioSerialPort, sa_smartbaud);
241 saStat.pktsent = 0;
242 saStat.pktrcvd = 0;
245 // Transport level variables
247 static timeUs_t sa_lastTransmissionMs = 0;
248 static uint8_t sa_outstanding = SA_CMD_NONE; // Outstanding command
249 static uint8_t sa_osbuf[32]; // Outstanding comamnd frame for retransmission
250 static int sa_oslen; // And associate length
252 static void saProcessResponse(uint8_t *buf, int len)
254 uint8_t resp = buf[0];
256 if (IS_RC_MODE_ACTIVE(BOXVTXCONTROLDISABLE)) {
257 sa_outstanding = SA_CMD_NONE;
259 return;
262 if (resp == sa_outstanding) {
263 sa_outstanding = SA_CMD_NONE;
264 } else if ((resp == SA_CMD_GET_SETTINGS_V2 ||
265 resp == SA_CMD_GET_SETTINGS_V21) &&
266 (sa_outstanding == SA_CMD_GET_SETTINGS)) {
267 sa_outstanding = SA_CMD_NONE;
268 } else {
269 saStat.ooopresp++;
270 dprintf(("processResponse: outstanding %d got %d\r\n", sa_outstanding, resp));
273 switch (resp) {
274 case SA_CMD_GET_SETTINGS_V21: // Version 2.1 Get Settings
275 case SA_CMD_GET_SETTINGS_V2: // Version 2 Get Settings
276 case SA_CMD_GET_SETTINGS: // Version 1 Get Settings
277 dprintf(("received settings\r\n"));
278 if (len < 7) {
279 break;
282 // From spec: "Bit 7-3 is holding the Smart audio version where 0 is V1, 1 is V2, 2 is V2.1"
283 // saDevice.version = 0 means unknown, 1 means Smart audio V1, 2 means Smart audio V2 and 3 means Smart audio V2.1
284 saDevice.version = (buf[0] == SA_CMD_GET_SETTINGS) ? 1 : ((buf[0] == SA_CMD_GET_SETTINGS_V2) ? 2 : 3);
285 saDevice.channel = buf[2];
286 uint8_t rawPowerValue = buf[3];
287 saDevice.mode = buf[4];
288 saDevice.freq = (buf[5] << 8) | buf[6];
290 // read pir and por flags to detect if the device will boot into pitmode.
291 // note that "quit pitmode without unsetting the pitmode flag" clears pir and por flags but the device will still boot into pitmode.
292 // therefore we ignore the pir and por flags while the device is not in pitmode
293 // actually, this is the whole reason the variable saDevice.willBootIntoPitMode exists.
294 // otherwise we could use saDevice.mode directly
295 if (saDevice.mode & SA_MODE_GET_PITMODE) {
296 bool newBootMode = (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) || (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE);
297 if (newBootMode != saDevice.willBootIntoPitMode) {
298 dprintf(("saProcessResponse: willBootIntoPitMode is now %s\r\n", newBootMode ? "true" : "false"));
300 saDevice.willBootIntoPitMode = newBootMode;
303 if (saDevice.version == 3) {
304 //read dbm based power levels
305 //aaaaaand promptly forget them. todo: write them into vtxtable pg and load it
306 if (len < 10) { //current power level in dbm field missing or power level length field missing or zero power levels reported
307 dprintf(("processResponse: V2.1 vtx didn't report any power levels\r\n"));
308 break;
310 saSupportedNumPowerLevels = constrain((int8_t)buf[8], 0, VTX_TABLE_MAX_POWER_LEVELS);
311 //SmartAudio seems to report buf[8] + 1 power levels, but one of them is zero.
312 //zero is indeed a valid power level to set the vtx to, but it activates pit mode.
313 //crucially, after sending 0 dbm, the vtx does NOT report its power level to be 0 dbm.
314 //instead, it reports whatever value was set previously and it reports to be in pit mode.
315 //for this reason, zero shouldn't be used as a normal power level in betaflight.
316 #ifdef USE_SMARTAUDIO_DPRINTF
317 if ( len < ( 9 + saSupportedNumPowerLevels )) {
318 dprintf(("processResponse: V2.1 vtx expected %d power levels but packet too short\r\n", saSupportedNumPowerLevels));
319 break;
321 if (len > (10 + saSupportedNumPowerLevels )) {
322 dprintf(("processResponse: V2.1 %d extra bytes found!\r\n", len - (10 + saSupportedNumPowerLevels)));
324 #endif
325 for ( int8_t i = 0; i < saSupportedNumPowerLevels; i++ ) {
326 saSupportedPowerValues[i] = buf[9 + i + 1];//+ 1 to skip the first power level, as mentioned above
329 dprintf(("processResponse: %d power values: %d, %d, %d, %d\r\n",
330 vtxTablePowerLevels, vtxTablePowerValues[0], vtxTablePowerValues[1],
331 vtxTablePowerValues[2], vtxTablePowerValues[3]));
332 //dprintf(("processResponse: V2.1 received vtx power value %d\r\n",buf[7]));
333 rawPowerValue = buf[7];
335 #ifdef USE_SMARTAUDIO_DPRINTF
336 int8_t prevPower = saDevice.power;
337 #endif
338 saDevice.power = 0;//set to unknown power level if the reported one doesnt match any of the known ones
339 dprintf(("processResponse: rawPowerValue is %d, legacy power is %d\r\n", rawPowerValue, buf[3]));
340 for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
341 if (rawPowerValue == vtxTablePowerValues[i]) {
342 #ifdef USE_SMARTAUDIO_DPRINTF
343 if (prevPower != i + 1) {
344 dprintf(("processResponse: power changed from index %d to index %d\r\n", prevPower, i + 1));
346 #endif
347 saDevice.power = i + 1;
352 DEBUG_SET(DEBUG_SMARTAUDIO, 0, saDevice.version * 100 + saDevice.mode);
353 DEBUG_SET(DEBUG_SMARTAUDIO, 1, saDevice.channel);
354 DEBUG_SET(DEBUG_SMARTAUDIO, 2, saDevice.freq);
355 DEBUG_SET(DEBUG_SMARTAUDIO, 3, saDevice.power);
356 break;
358 case SA_CMD_SET_POWER: // Set Power
359 break;
361 case SA_CMD_SET_CHAN: // Set Channel
362 break;
364 case SA_CMD_SET_FREQ: // Set Frequency
365 if (len < 5) {
366 break;
369 const uint16_t freq = (buf[2] << 8) | buf[3];
371 if (freq & SA_FREQ_GETPIT) {
372 saDevice.orfreq = freq & SA_FREQ_MASK;
373 dprintf(("saProcessResponse: GETPIT freq %d\r\n", saDevice.orfreq));
374 } else if (freq & SA_FREQ_SETPIT) {
375 saDevice.orfreq = freq & SA_FREQ_MASK;
376 dprintf(("saProcessResponse: SETPIT freq %d\r\n", saDevice.orfreq));
377 } else {
378 saDevice.freq = freq;
379 dprintf(("saProcessResponse: SETFREQ freq %d\r\n", freq));
381 break;
383 case SA_CMD_SET_MODE: // Set Mode
384 dprintf(("saProcessResponse: SET_MODE 0x%x (pir %s, por %s, pitdsbl %s, %s)\r\n",
385 buf[2], (buf[2] & 1) ? "on" : "off", (buf[2] & 2) ? "on" : "off", (buf[3] & 4) ? "on" : "off",
386 (buf[4] & 8) ? "unlocked" : "locked"));
387 break;
389 default:
390 saStat.badcode++;
391 return;
394 if (memcmp(&saDevice, &saDevicePrev, sizeof(smartAudioDevice_t))) {
395 #ifdef USE_CMS //if changes then trigger saCms update
396 saCmsResetOpmodel();
397 #endif
398 #ifdef USE_SMARTAUDIO_DPRINTF // Debug
399 saPrintSettings();
400 #endif
402 saDevicePrev = saDevice;
404 #ifdef USE_VTX_COMMON
405 // Todo: Update states in saVtxDevice?
406 #endif
408 #ifdef USE_CMS
409 // Export current device status for CMS
410 saCmsUpdate();
411 saUpdateStatusString();
412 #endif
416 // Datalink
419 static void saReceiveFrame(uint8_t c)
422 static enum saFramerState_e {
423 S_WAITPRE1, // Waiting for preamble 1 (0xAA)
424 S_WAITPRE2, // Waiting for preamble 2 (0x55)
425 S_WAITRESP, // Waiting for response code
426 S_WAITLEN, // Waiting for length
427 S_DATA, // Receiving data
428 S_WAITCRC, // Waiting for CRC
429 } state = S_WAITPRE1;
431 static int len;
432 static int dlen;
434 switch (state) {
435 case S_WAITPRE1:
436 if (c == 0xAA) {
437 state = S_WAITPRE2;
438 } else {
439 state = S_WAITPRE1; // Don't need this (no change)
441 break;
443 case S_WAITPRE2:
444 if (c == 0x55) {
445 state = S_WAITRESP;
446 } else {
447 saStat.badpre++;
448 state = S_WAITPRE1;
450 break;
452 case S_WAITRESP:
453 sa_rbuf[0] = c;
454 state = S_WAITLEN;
455 break;
457 case S_WAITLEN:
458 sa_rbuf[1] = c;
459 len = c;
461 if (len > SA_MAX_RCVLEN - 2) {
462 saStat.badlen++;
463 state = S_WAITPRE1;
464 } else if (len == 0) {
465 state = S_WAITCRC;
466 } else {
467 dlen = 0;
468 state = S_DATA;
470 break;
472 case S_DATA:
473 // XXX Should check buffer overflow (-> saerr_overflow)
474 sa_rbuf[2 + dlen] = c;
475 if (++dlen == len) {
476 state = S_WAITCRC;
478 break;
480 case S_WAITCRC:
481 if (CRC8(sa_rbuf, 2 + len) == c) {
482 // Got a response
483 saProcessResponse(sa_rbuf, len + 2);
484 saStat.pktrcvd++;
485 } else if (sa_rbuf[0] & 1) {
486 // Command echo
487 // XXX There is an exceptional case (V2 response)
488 // XXX Should check crc in the command format?
489 } else {
490 saStat.crc++;
492 state = S_WAITPRE1;
493 break;
497 static void saSendFrame(uint8_t *buf, int len)
499 if (!IS_RC_MODE_ACTIVE(BOXVTXCONTROLDISABLE)) {
500 switch (smartAudioSerialPort->identifier) {
501 case SERIAL_PORT_SOFTSERIAL1:
502 case SERIAL_PORT_SOFTSERIAL2:
503 break;
504 default:
505 serialWrite(smartAudioSerialPort, 0x00); // Generate 1st start bit
506 break;
509 for (int i = 0 ; i < len ; i++) {
510 serialWrite(smartAudioSerialPort, buf[i]);
513 saStat.pktsent++;
514 } else {
515 sa_outstanding = SA_CMD_NONE;
518 sa_lastTransmissionMs = millis();
522 * Retransmission and command queuing
524 * The transport level support includes retransmission on response timeout
525 * and command queueing.
527 * Resend buffer:
528 * The smartaudio returns response for valid command frames in no less
529 * than 60msec, which we can't wait. So there's a need for a resend buffer.
531 * Command queueing:
532 * The driver autonomously sends GetSettings command for auto-bauding,
533 * asynchronous to user initiated commands; commands issued while another
534 * command is outstanding must be queued for later processing.
535 * The queueing also handles the case in which multiple commands are
536 * required to implement a user level command.
539 // Retransmission
541 static void saResendCmd(void)
543 saSendFrame(sa_osbuf, sa_oslen);
546 static void saSendCmd(uint8_t *buf, int len)
548 for (int i = 0 ; i < len ; i++) {
549 sa_osbuf[i] = buf[i];
552 sa_oslen = len;
553 sa_outstanding = (buf[2] >> 1);
555 saSendFrame(sa_osbuf, sa_oslen);
558 // Command queue management
560 typedef struct saCmdQueue_s {
561 uint8_t *buf;
562 int len;
563 } saCmdQueue_t;
565 #define SA_QSIZE 6 // 1 heartbeat (GetSettings) + 2 commands + 1 slack
566 static saCmdQueue_t sa_queue[SA_QSIZE];
567 static uint8_t sa_qhead = 0;
568 static uint8_t sa_qtail = 0;
570 static bool saQueueEmpty(void)
572 return sa_qhead == sa_qtail;
575 static bool saQueueFull(void)
577 return ((sa_qhead + 1) % SA_QSIZE) == sa_qtail;
580 static void saQueueCmd(uint8_t *buf, int len)
582 if (saQueueFull()) {
583 return;
586 sa_queue[sa_qhead].buf = buf;
587 sa_queue[sa_qhead].len = len;
588 sa_qhead = (sa_qhead + 1) % SA_QSIZE;
591 static void saSendQueue(void)
593 if (saQueueEmpty()) {
594 return;
597 saSendCmd(sa_queue[sa_qtail].buf, sa_queue[sa_qtail].len);
598 sa_qtail = (sa_qtail + 1) % SA_QSIZE;
601 // Individual commands
603 static void saGetSettings(void)
605 static uint8_t bufGetSettings[5] = {0xAA, 0x55, SACMD(SA_CMD_GET_SETTINGS), 0x00, 0x9F};
607 dprintf(("smartAudioGetSettings\r\n"));
608 saQueueCmd(bufGetSettings, 5);
611 static bool saValidateFreq(uint16_t freq)
613 return (freq >= VTX_SMARTAUDIO_MIN_FREQUENCY_MHZ && freq <= VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ);
616 void saSetFreq(uint16_t freq)
618 static uint8_t buf[7] = { 0xAA, 0x55, SACMD(SA_CMD_SET_FREQ), 2 };
619 static uint8_t switchBuf[7];
621 if (freq & SA_FREQ_GETPIT) {
622 dprintf(("smartAudioSetFreq: GETPIT\r\n"));
623 } else if (freq & SA_FREQ_SETPIT) {
624 dprintf(("smartAudioSetFreq: SETPIT %d\r\n", freq & SA_FREQ_MASK));
625 } else {
626 dprintf(("smartAudioSetFreq: SET %d\r\n", freq));
629 buf[4] = (freq >> 8) & 0xff;
630 buf[5] = freq & 0xff;
631 buf[6] = CRC8(buf, 6);
633 // Need to work around apparent SmartAudio bug when going from 'channel'
634 // to 'user-freq' mode, where the set-freq command will fail if the freq
635 // value is unchanged from the previous 'user-freq' mode
636 if ((saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) == 0 && freq == saDevice.freq) {
637 memcpy(&switchBuf, &buf, sizeof(buf));
638 const uint16_t switchFreq = freq + ((freq == VTX_SMARTAUDIO_MAX_FREQUENCY_MHZ) ? -1 : 1);
639 switchBuf[4] = (switchFreq >> 8);
640 switchBuf[5] = switchFreq & 0xff;
641 switchBuf[6] = CRC8(switchBuf, 6);
643 saQueueCmd(switchBuf, 7);
645 // need to do a 'get' between the 'set' commands to keep tracking vars in sync
646 saGetSettings();
649 saQueueCmd(buf, 7);
652 void saSetPitFreq(uint16_t freq)
654 saSetFreq(freq | SA_FREQ_SETPIT);
657 #if 0
658 static void saGetPitFreq(void)
660 saDoDevSetFreq(SA_FREQ_GETPIT);
662 #endif
664 void saSetMode(int mode)
666 static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_MODE), 1 };
668 buf[4] = (mode & 0x3f) | saLockMode;
669 if (saDevice.version >= 3 && (mode & SA_MODE_CLR_PITMODE) &&
670 ((mode & SA_MODE_SET_IN_RANGE_PITMODE) || (mode & SA_MODE_SET_OUT_RANGE_PITMODE))) {
671 saDevice.willBootIntoPitMode = true;//quit pitmode without unsetting flag.
672 //the response will just say pit=off but the device will still go into pitmode on reboot.
673 //therefore we have to memorize this change here.
675 dprintf(("saSetMode(0x%x): pir=%s por=%s pitdsbl=%s %s\r\n", mode, (mode & 1) ? "on " : "off", (mode & 2) ? "on " : "off",
676 (mode & 4)? "on " : "off", (mode & 8) ? "locked" : "unlocked"));
677 buf[5] = CRC8(buf, 5);
679 saQueueCmd(buf, 6);
683 bool vtxSmartAudioInit(void)
685 #if !defined(USE_VTX_TABLE)
686 for (int8_t i = 0; i < VTX_SMARTAUDIO_POWER_COUNT + 1; i++) {
687 saSupportedPowerLabelPointerArray[i] = saSupportedPowerLabels[i];
689 #endif
690 #ifdef USE_SMARTAUDIO_DPRINTF
691 // Setup debugSerialPort
693 debugSerialPort = openSerialPort(DPRINTF_SERIAL_PORT, FUNCTION_NONE, NULL, NULL, 115200, MODE_RXTX, 0);
694 if (debugSerialPort) {
695 setPrintfSerialPort(debugSerialPort);
697 dprintf(("smartAudioInit: OK\r\n"));
698 #endif
700 // Note, for SA, which uses bidirectional mode, would normally require pullups.
701 // the SA protocol instead requires pulldowns, and therefore uses SERIAL_BIDIR_PP_PD instead of SERIAL_BIDIR_PP
702 const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_VTX_SMARTAUDIO);
703 if (portConfig) {
704 portOptions_e portOptions = SERIAL_STOPBITS_2 | SERIAL_BIDIR_NOPULL;
705 #if defined(USE_VTX_COMMON)
706 portOptions = portOptions | (vtxConfig()->halfDuplex ? SERIAL_BIDIR | SERIAL_BIDIR_PP_PD : SERIAL_UNIDIR);
707 #else
708 portOptions = SERIAL_BIDIR;
709 #endif
711 smartAudioSerialPort = openSerialPort(portConfig->identifier, FUNCTION_VTX_SMARTAUDIO, NULL, NULL, 4800, MODE_RXTX, portOptions);
714 if (!smartAudioSerialPort) {
715 return false;
718 for (int8_t i = 0; i < VTX_SMARTAUDIO_POWER_COUNT; i++) {
719 saSupportedPowerValues[i] = 1;
722 dprintf(("vtxSmartAudioInit %d power levels recorded\r\n", vtxTablePowerLevels));
726 vtxCommonSetDevice(&vtxSmartAudio);
727 #ifndef USE_VTX_TABLE
728 vtxTableSetFactoryBands(true);
729 #endif
731 vtxInit();
733 return true;
736 #define SA_INITPHASE_START 0
737 #define SA_INITPHASE_WAIT_SETTINGS 1 // SA_CMD_GET_SETTINGS was sent and waiting for reply.
738 #define SA_INITPHASE_WAIT_PITFREQ 2 // SA_FREQ_GETPIT sent and waiting for reply.
739 #define SA_INITPHASE_DONE 3
741 static void vtxSAProcess(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs)
743 UNUSED(vtxDevice);
744 UNUSED(currentTimeUs);
746 static char initPhase = SA_INITPHASE_START;
748 if (smartAudioSerialPort == NULL) {
749 return;
752 while (serialRxBytesWaiting(smartAudioSerialPort) > 0) {
753 uint8_t c = serialRead(smartAudioSerialPort);
754 saReceiveFrame((uint16_t)c);
757 // Re-evaluate baudrate after each frame reception
758 saAutobaud();
760 switch (initPhase) {
761 case SA_INITPHASE_START:
762 saGetSettings();
763 //saSendQueue();
764 initPhase = SA_INITPHASE_WAIT_SETTINGS;
765 break;
767 case SA_INITPHASE_WAIT_SETTINGS:
768 // Don't send SA_FREQ_GETPIT to V1 device; it act as plain SA_CMD_SET_FREQ,
769 // and put the device into user frequency mode with uninitialized freq.
770 // Also don't send it to V2.1 for the same reason.
771 if (saDevice.version) {
772 if (saDevice.version == 2) {
773 saSetFreq(SA_FREQ_GETPIT);
774 initPhase = SA_INITPHASE_WAIT_PITFREQ;
775 } else {
776 initPhase = SA_INITPHASE_DONE;
779 #if !defined(USE_VTX_TABLE)
780 if (saDevice.version == 1) {//this is kind of ugly. use fixed tables and set a pointer to them instead?
781 saSupportedPowerValues[0] = 7;
782 saSupportedPowerValues[1] = 16;
783 saSupportedPowerValues[2] = 25;
784 saSupportedPowerValues[3] = 40;
785 } else if (saDevice.version == 2) {
786 saSupportedPowerValues[0] = 0;
787 saSupportedPowerValues[1] = 1;
788 saSupportedPowerValues[2] = 2;
789 saSupportedPowerValues[3] = 3;
792 //without USE_VTX_TABLE, fill vtxTable variables with default settings (instead of loading them from PG)
793 vtxTablePowerLevels = constrain(saSupportedNumPowerLevels, 0, VTX_SMARTAUDIO_POWER_COUNT);
794 if (saDevice.version >= 3) {
795 for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
796 //ideally we would convert dbm to mW here
797 tfp_sprintf(saSupportedPowerLabels[i + 1], "%3d", constrain(saSupportedPowerValues[i], 0, 999));
800 for (int8_t i = 0; i < vtxTablePowerLevels; i++) {
801 vtxTablePowerValues[i] = saSupportedPowerValues[i];
803 for (int8_t i = 0; i < vtxTablePowerLevels + 1; i++) {
804 vtxTablePowerLabels[i] = saSupportedPowerLabels[i];
806 dprintf(("vtxSAProcess init phase vtxTablePowerLevels set to %d\r\n", vtxTablePowerLevels));
807 #endif
809 if (saDevice.version >= 2 ) {
810 //did the device boot up in pit mode on its own?
811 saDevice.willBootIntoPitMode = (saDevice.mode & SA_MODE_GET_PITMODE) ? true : false;
812 dprintf(("sainit: willBootIntoPitMode is %s\r\n", saDevice.willBootIntoPitMode ? "true" : "false"));
815 break;
817 case SA_INITPHASE_WAIT_PITFREQ:
818 if (saDevice.orfreq) {
819 initPhase = SA_INITPHASE_DONE;
821 break;
823 case SA_INITPHASE_DONE:
824 break;
827 // Command queue control
829 timeMs_t nowMs = millis(); // Don't substitute with "currentTimeUs / 1000"; sa_lastTransmissionMs is based on millis().
830 static timeMs_t lastCommandSentMs = 0; // Last non-GET_SETTINGS sent
832 if ((sa_outstanding != SA_CMD_NONE) && (nowMs - sa_lastTransmissionMs > SMARTAUDIO_CMD_TIMEOUT)) {
833 // Last command timed out
834 dprintf(("process: resending 0x%x\r\n", sa_outstanding));
835 // XXX Todo: Resend termination and possible offline transition
836 saResendCmd();
837 lastCommandSentMs = nowMs;
838 } else if (!saQueueEmpty()) {
839 // Command pending. Send it.
840 dprintf(("process: sending queue\r\n"));
841 saSendQueue();
842 lastCommandSentMs = nowMs;
843 } else if ((nowMs - lastCommandSentMs < SMARTAUDIO_POLLING_WINDOW)
844 && (nowMs - sa_lastTransmissionMs >= SMARTAUDIO_POLLING_INTERVAL)) {
845 dprintf(("process: sending status change polling\r\n"));
846 saGetSettings();
847 saSendQueue();
850 #ifdef USE_VTX_COMMON
851 // Interface to common VTX API
853 vtxDevType_e vtxSAGetDeviceType(const vtxDevice_t *vtxDevice)
855 UNUSED(vtxDevice);
856 return VTXDEV_SMARTAUDIO;
859 static bool vtxSAIsReady(const vtxDevice_t *vtxDevice)
861 #ifndef USE_VTX_TABLE
862 if (vtxDevice != NULL && saDevice.power == 0) {
863 return false;
864 //wait until power reading exists
865 //this is needed bc the powervalues are loaded into vtxTableXXX after the first settings are received
866 //thus the first time processResponse runs its index lookup it won't find anything and no power is recorded
867 //this waits until after the second time settings are received which will actually find something
868 //this check is not needed with USE_VTX_TABLE as the table is loaded from pg before smartaudio is even started
869 //in fact, with USE_VTX_TABLE this check could end up paralyzing the smartaudio implementation if the user has
870 //chosen to omit a power state in the vtxtable but the vtx happens to power up in that state for whatever reason
872 #endif
873 return vtxDevice != NULL && saDevice.version != 0;
876 static bool saValidateBandAndChannel(uint8_t band, uint8_t channel)
878 return (band >= VTX_SMARTAUDIO_MIN_BAND && band <= vtxTableBandCount &&
879 channel >= VTX_SMARTAUDIO_MIN_CHANNEL && channel <= vtxTableChannelCount);
882 static void vtxSASetBandAndChannel(vtxDevice_t *vtxDevice, uint8_t band, uint8_t channel)
884 UNUSED(vtxDevice);
885 if (saValidateBandAndChannel(band, channel)) {
886 static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_CHAN), 1 };
888 buf[4] = SA_BANDCHAN_TO_DEVICE_CHVAL(band, channel);
889 buf[5] = CRC8(buf, 5);
890 dprintf(("vtxSASetBandAndChannel set index band %d channel %d value sent 0x%x\r\n", band, channel, buf[4]));
892 //this will clear saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ
893 saQueueCmd(buf, 6);
897 static void vtxSASetPowerByIndex(vtxDevice_t *vtxDevice, uint8_t index)
899 static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_POWER), 1 };
901 if (!vtxSAIsReady(vtxDevice)) {
902 return;
905 uint16_t powerValue = 0;
906 if (!vtxCommonLookupPowerValue(vtxDevice, index, &powerValue)) {
907 dprintf(("saSetPowerByIndex: cannot get power level %d, only levels 1 through %d supported", index,
908 vtxTablePowerLevels));
909 return;
912 buf[4] = powerValue;
913 dprintf(("saSetPowerByIndex: index %d, value %d\r\n", index, buf[4]));
914 if (saDevice.version == 3) {
915 buf[4] |= 128;//set MSB to indicate set power by dbm
917 buf[5] = CRC8(buf, 5);
918 saQueueCmd(buf, 6);
921 static void vtxSASetPitMode(vtxDevice_t *vtxDevice, uint8_t onoff)
923 if (!vtxSAIsReady(vtxDevice) || saDevice.version < 2) {
924 return;
927 if (onoff && saDevice.version < 3) {
928 // Smart Audio prior to V2.1 can not turn pit mode on by software.
929 return;
932 if (saDevice.version >= 3 && !saDevice.willBootIntoPitMode) {
933 if (onoff) {
934 // enable pitmode using SET_POWER command with 0 dbm.
935 // This enables pitmode without causing the device to boot into pitmode next power-up
936 static uint8_t buf[6] = { 0xAA, 0x55, SACMD(SA_CMD_SET_POWER), 1 };
937 buf[4] = 0 | 128;
938 buf[5] = CRC8(buf, 5);
939 saQueueCmd(buf, 6);
940 dprintf(("vtxSASetPitMode: set power to 0 dbm\r\n"));
941 } else {
942 saSetMode(SA_MODE_CLR_PITMODE);
943 dprintf(("vtxSASetPitMode: clear pitmode permanently"));
945 return;
948 uint8_t newMode = onoff ? 0 : SA_MODE_CLR_PITMODE;
950 if (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE) {
951 newMode |= SA_MODE_SET_OUT_RANGE_PITMODE;
954 if ((saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) || (onoff && newMode == 0)) {
955 // ensure when turning on pit mode that pit mode gets actually enabled
956 newMode |= SA_MODE_SET_IN_RANGE_PITMODE;
958 dprintf(("vtxSASetPitMode %s with stored mode 0x%x por %s, pir %s, newMode 0x%x\r\n", onoff ? "on" : "off", saDevice.mode,
959 (saDevice.mode & SA_MODE_GET_OUT_RANGE_PITMODE) ? "on" : "off",
960 (saDevice.mode & SA_MODE_GET_IN_RANGE_PITMODE) ? "on" : "off" , newMode));
963 saSetMode(newMode);
965 return;
968 static void vtxSASetFreq(vtxDevice_t *vtxDevice, uint16_t freq)
970 if (!vtxSAIsReady(vtxDevice)) {
971 return;
974 if (saValidateFreq(freq)) {
975 saSetFreq(freq);
979 static bool vtxSAGetBandAndChannel(const vtxDevice_t *vtxDevice, uint8_t *pBand, uint8_t *pChannel)
981 if (!vtxSAIsReady(vtxDevice)) {
982 return false;
985 if (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) {
986 *pBand = 0;
987 *pChannel = 0;
988 return true;
989 } else {
990 *pBand = SA_DEVICE_CHVAL_TO_BAND(saDevice.channel);
991 *pChannel = SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel);
992 return true;
996 static bool vtxSAGetPowerIndex(const vtxDevice_t *vtxDevice, uint8_t *pIndex)
998 if (!vtxSAIsReady(vtxDevice)) {
999 return false;
1002 *pIndex = saDevice.power;//power levels are 1-based to match vtxtables with one more label than value
1003 return true;
1006 static bool vtxSAGetFreq(const vtxDevice_t *vtxDevice, uint16_t *pFreq)
1008 if (!vtxSAIsReady(vtxDevice)) {
1009 return false;
1012 // if not in user-freq mode then convert band/chan to frequency
1013 *pFreq = (saDevice.mode & SA_MODE_GET_FREQ_BY_FREQ) ? saDevice.freq :
1014 vtxCommonLookupFrequency(&vtxSmartAudio,
1015 SA_DEVICE_CHVAL_TO_BAND(saDevice.channel),
1016 SA_DEVICE_CHVAL_TO_CHANNEL(saDevice.channel));
1017 return true;
1020 static bool vtxSAGetStatus(const vtxDevice_t *vtxDevice, unsigned *status)
1022 if (!vtxSAIsReady(vtxDevice) || saDevice.version < 2) {
1023 return false;
1026 *status = (saDevice.mode & SA_MODE_GET_PITMODE) ? VTX_STATUS_PIT_MODE : 0;
1028 return true;
1031 static uint8_t vtxSAGetPowerLevels(const vtxDevice_t *vtxDevice, uint16_t *levels, uint16_t *powers)
1033 if (!vtxSAIsReady(vtxDevice) || saDevice.version < 2) {
1034 return 0;
1037 for (uint8_t i = 0; i < saSupportedNumPowerLevels; i++) {
1038 levels[i] = saSupportedPowerValues[i];
1039 uint16_t power = (uint16_t)powf(10.0f, levels[i] / 10.0f);
1041 if (levels[i] > 14) {
1042 // For powers greater than 25mW round up to a multiple of 50 to match expectations
1043 power = 50 * ((power + 25) / 50);
1046 powers[i] = power;
1049 return saSupportedNumPowerLevels;
1052 #define VTX_CUSTOM_DEVICE_STATUS_SIZE 5
1054 static void vtxSASerializeCustomDeviceStatus(const vtxDevice_t *vtxDevice, sbuf_t *dst)
1056 UNUSED(vtxDevice);
1057 sbufWriteU8(dst, VTX_CUSTOM_DEVICE_STATUS_SIZE);
1058 sbufWriteU8(dst, saDevice.version);
1059 sbufWriteU8(dst, saDevice.mode);
1060 sbufWriteU16(dst, saDevice.orfreq); // pit frequency
1061 sbufWriteU8(dst, saDevice.willBootIntoPitMode);
1064 #undef VTX_CUSTOM_DEVICE_STATUS_SIZE
1066 static const vtxVTable_t saVTable = {
1067 .process = vtxSAProcess,
1068 .getDeviceType = vtxSAGetDeviceType,
1069 .isReady = vtxSAIsReady,
1070 .setBandAndChannel = vtxSASetBandAndChannel,
1071 .setPowerByIndex = vtxSASetPowerByIndex,
1072 .setPitMode = vtxSASetPitMode,
1073 .setFrequency = vtxSASetFreq,
1074 .getBandAndChannel = vtxSAGetBandAndChannel,
1075 .getPowerIndex = vtxSAGetPowerIndex,
1076 .getFrequency = vtxSAGetFreq,
1077 .getStatus = vtxSAGetStatus,
1078 .getPowerLevels = vtxSAGetPowerLevels,
1079 .serializeCustomDeviceStatus = vtxSASerializeCustomDeviceStatus,
1081 #endif // VTX_COMMON
1084 #endif // VTX_SMARTAUDIO