Статья посвящена исследованию не сильно документированных возможностей управления параметрами FPV видеопередатчиков (VTX), таких как TBS SmartAudio и IRC Tramp и использованию в робосистемах, для управления переключением каналов и мощностью при помощи кода. Материал позволит упростить работу с видеопередатчиком и сэкономить время, тем, кто как и я, столкнулся с отсутствием библиотек и работающего кода для управления параметрами видеопередатчика.
Код, созданный в результате решения этой проблемы, можно скачать тут: https://github.com/RandyReover/VTXControl
Сокращения:
VTX(video transmitter, видеопередатчик),
AP (ArduPilot, система пилотирования дронов и не только дронов),
BF (BetaFlight, система пилотирования дронов),
SA(TBS SmartAudio, S.Audio),
IRC(одно из кратких обозначений протокола IRC Tramp),
MCU (micro controller unit, плата микроконтроллера).
С годов 15-16х в видеопередатчиках (далее VTX для краткости) появились новые интересные пины, помеченные как SmartAudio или IRC, или Tramp. Производители чаще просто упоминали в описаниях, что VTX поддерживает SmartAudio или IRC Tramp, а дальше молчок про то, что это такое и зачем и “как это работает”. Максимум, сейчас снабжают специальными json файлами настроек для использования в BF/AP и в Интернет можно встретить немало инструкций по подключению VTX к контроллеру полета и настройке работы с BF/AP.
В историю создания этих фич вдаваться не буду, тем более что если про SmartAudio что-то известно доподлинно (а именно, что создан компанией TeamBlackSheep(TBS), он документирован, и компания периодически обновляет версии документа), то про IRC Tramp нет ничего, кроме того, что он есть.
Пользователям дронов эти фичи известны как возможность управления видеопередатчиком через провод, программно, а не кнопкодавством на самом передатчике и реализовано это управление в таких системах управления дронами и не только дронами, как BetaFlight, ArduPilot и другими, менее известными . Известно, что SmartAudio и Tramp фактически протоколы, реализованные на однопроводном UART, т.е полудуплексном UART (устройство управления(назовем кратко MCU) и VTX постоянно находятся в режиме listen, MCU шлет запрос/команду и начинает слушать, VTX отвечает на запросы, выполняет команды(иногда молчаливо)).
Подобные фичи понадобились мне самому, так как появилась проблема пересечения каналов, когда твой робот вдруг начинает принимать видеотрансляцию от другого робота (естественно встречались ситуации наоборот). Добраться до VTX в роботе не всегда просто и быстро, да и переключение каналов надо делать с мониторингом, дабы не переключиться опять на занятый кем-то канал. Некоторые конструкторы роботов решают проблему просто - ставят мощный передатчик, выставляют мощность на максимум и всё, проблемы индейцев шерифа не волнуют. Но это не выход, при большой мощности передатчик греется и потребляет гораздо больше и надо решать и эти проблемы.
Поэтому решено было разобраться с переключением каналов программно. Мальчиком для битья выступил сначала VTX Eachine TX5258, поддерживающий SmartAudio, следующим оказался JHEMCU RuiBet Tran3016W, поддерживающий Tramp.
Первой проблемой для реализации функционала управления возникла проблема реализации однопроводного uart. Была подобрана на GitHub библиотечка SoftwareSerialWithHalfDuplex, подходящая по функционалу и способная работать по одному пину (скажу сразу - реализация на HardwareSerial не подходила, т.к аппаратные UART были заняты, но собственно при необходимости можно было заменить SoftwareSerialWithHalfDuplex на полнодуплексную реализацию HardwareSerial).
Дальше я углубился в коды Betaflight и ArduPilot, а также поиск на Github по реализации этих протоколов. Собственно, более-менее реализованными они были только в BF и AP, поэтому сконцентрировался на анализе их кода(при том, что в AP коде часто встречались комментарии, что код взят из BF).
Из всего этого исследования родился код библиотечки VTXControl, которая способна была работать с обоими протоколами, и взяла те наработки с этими протоколами, каковые были в коде BF/AP.
Итак, согласно документации по SmartAudio этот протокол работает на скорости 4800bps, 8 датабит, один старт бит, 2 стопбита, 3.3v логика(это важно, т.к следует предположить, что не все передатчики толерантны к 5вольтовой логике и может быть придется использовать конвертор логики или мост для понижения сигнала), мой TX5258 оказался толерантен. На более продвинутых MCU, например STM32, можно подтягивать питание порта (включая режим OUTPUT PULLDOWN). Согласно документации TBS, передатчик нагревается, поэтому скорость протокола может варьироваться +5/-5%.
Из-за того, что SoftwareSerialWithHalfDuplex не знал про разные конфигурации передачи данных (знал он только о инверсной логике, но реализована была только одна стандартная 8N1), пришлось дополнить этот класс работой с различными конфигурациями, и чтобы можно было работать с форматом 8 датабит, один старт бит, 2 стопбита (8N2). Также, согласно документации, необходимо сделать линию связи low перед началом передачи или заслать пустой байт (0x00).
Кроме этого, режим SA на передатчике TX5258 необходимо включить аппаратно, согласно документации на передатчик, необходимо держать кнопку 10 секунд и отпускать ее когда замигает точка. Появление точки на дисплее и будет означать, что режим SmartAudio включен.
Протокол Tramp в этом плане нетребователен (это уже согласно коду BF/AP, т.к документации по Tramp нет) - 9600bps, 8N1, 5v логика.
Итак, транспорт есть, пора бы покомандовать VTX-ом.
Следующим шагом стало изучение команд-запросов к VTX, их формат, и правила/особенности проведения запросов.
В SmartAudio на текущий момент (согласно документации) реализовано две версии (v1 и v2) протокола (хотя код BF/AP говорит, что есть ещё некая v2.1, нашел я его упоминания в документации на VTX TBS Unify Pro32 , где есть ссылка и на последнюю ревизию протокола SmartAudio v2.1 ). Чтобы узнать, какая версия используется на текущем передатчике, необходимо сделать запрос SMARTAUDIO_CMD_GET_SETTINGS (0x01, TBS в документации требует сдвигать эту команду влево с заполнением крайнего бита, т.ак что BF/AP правильно сразу обозначают эту команду как 0x03). В зависимости от версии SA меняется и разбор пакета ответа, и параметры запросов - это важно помнить. Причем переключиться в режим некоих 1200 или 1600 mW в первой версии протокола не получится, ибо нет данных(не документировано выше 800mW), что засылать на передатчик. Но наверное можно вычислить, выставив мощность на максимум кнопкой на передатчике, а уж потом засылать запрос о текущих параметрах передатчика, чтобы получить кодированное значение. Слава богам на TX5258 была реализована версия 2 SA, что позволило избежать сложностей, но максимальная его мощность - 800mW, вполне вписывалась в документированное.
Ну вот мы сформировали запрос. Запрос фиксированный:
{ 0xAA, 0x55, 0x03, 0x00, 0x9F }
,
где первые два байта это SMARTAUDIO_SYNC_BYTE и SMARTAUDIO_HEADER_BYTE, они там всегда в запросах и ответах VTX. Дальше идут байты заголовка(2 байта): cmd и len (длина данных после заголовка),но так как длина - 0, то завершает пакет контрольная сумма(crc). Как говорил выше - этот запрос фиксирован, так что и crc здесь неизменна. О процедуре вычисления контрольной суммы упоминать не буду, она документирована, к тому же код BF/AP также содержит куда более краткую версию этой процедуры.
VTX подключен, запитан (т.к ему надо больше 5 вольт для работы, поэтому питание от MCU туда не пробросить. Важно: земля должна быть общая), запрос послан, но передатчик молчит, как партизан на допросе. Вспомнилось про +5/-5% разброс скорости и был реализован функционал smartbauding (понятие заимствовано из кода BF/AP, функционал тоже) - то есть подбор скорости, на которой он воспримет мои запросы. Увы - молчит.
Углубился в гугление темы и открылись мне глубины истины. Оказывается авторы BF сильно жаловались на то, что многие производители VTX не захотели покупать лицензирование от TBS и реализовали протокол SA самостоятельно (и даже на кодах BF до v3.3. Определили это благодаря багу в версиях до 3.3 где отсылался дополнительный пустой байт идущий в конце пакета. В итоге передатчики AKK/RDQ спокойно работали с BF версии до 3,3 а с версиями после они не работали). И вообще разработчики жаловались на poor implementation этого протокола у различных производителей VTX, подобное они называли клонами и всячески рекомендовали брать передатчики TBS, однако под давлением общественности, всё-таки вернули “баг” код для поддержки передатчиков AKK/RDQ, добавив специальный define. То есть стоило мне ожидать чего-то такого эдакого от TX5258. В итоге так и сработало - запись лишнего байта после посылки пакета и передатчик ответил. Но ответил он тоже нестандартно, аж с двумя пустыми байтами вначале, и одним в конце пакета, и с совершенно непонятно как вычисляющейся crc. Пришлось несколько расслабить процедуру приема пакета для пропуска незначащих байтов в ожидании SMARTAUDIO_SYNC_BYTE, игнорировать crc, ну дальше парсинг пакета и дело пошло. Вдаваться в систему команд SA не буду - она хорошо документирована, их описание также можно посмотреть в прилагаемом VTX_SmartAudio.h.
С Tramp все было проще, но там тоже передатчик молчал. Проблема оказалась в вычислении crc и тут код от AP был корректнее чем от BF, считать crc надо со второго байта по 13й (включительно), в 14-й пишем crc, 15-й - пустой байт. Формат пакетов Tramp фиксирован - 16 байт, первый байт - это всегда длина пакета 0x0F (он же TRAMP_SYNC_START), последний - 0x00 (он же TRAMP_SYNC_STOP).
В отличие от SA (где протокол запускается аппаратно, кнопкодавством), протокол Tramp необходимо инициировать командой TRAMP_COMMAND_CMD_RF (0x72 или ‘r’) и только после получения ответа (который можно не разбирать, а просто поднять флажок initialized = true) можно посылать запросы (т.е требующие ответа от VTX) и команды (не требующие ответа от VTX). Набор команд/запросов в Tramp побогаче, но запрашивать температуру на VTX мне не было необходимости, поэтому подобный запрос я не реализовал. Также информация о минимальной и максимальной частоте работы передатчика была неинтересна, т.к частоты/каналы давно выделены и стандартизированы и описаны в доках по VTX, поэтому функционал базировался на фиксированных данных о каналах, частотах и мощностях,
Особенностью Tramp также является то, что после команды TRAMP_COMMAND_SET_POWER или TRAMP_COMMAND_SET_FREQ не нужно ждать ответа от передатчика, для подтверждения принятия данных, поэтому я их называю командами. Поэтому стоит реализовывать метод проверки корректности установки параметров таким образом: сначала идет команда установки параметра (а перед ней идет проверка инициации протокола. Если не инициирован - необходимо инициировать запросом TRAMP_COMMAND_CMD_RF), (мощности, частоты/канала, затем идет запрос getSettings (TRAMP_COMMAND_GET_CONFIG), где уже и проверяется, установлен ли тот или иной параметр или нет, и правильно ли установлен. Посмотреть систему команд можно в файле VTX_Tramp.h, она хорошо прокомментирована мной.
Ну вот все у меня и заработало и с Tramp-ом также.
Отдельно хотелось бы упомянуть такое понятие как PitMode. Это режим VTX, используемый когда, когда дрон находится в состоянии disarmed - то есть он не выключен, но и ничего не делает, он находится на земле, это режим энергосбережения, режим ожидания (standby) в моем понимании. В этом состоянии стоило бы вводить VTX в состояние PitMode, когда его энергопотребление на минимуме, он работает на минимальной мощности, и на специальной частоте. Этот функционал был мне не нужен, т.к код готовился не для дрона, и в моем случае, когда система либо включена (armed), либо выключена, использование PitMode было не нужно.
Резюмируя:
Могу сказать, что постарался сделать код универсальным, для поддержки обоих протоколов, но протоколы протоколами, а как поведет себя конкретно ваш передатчик, я не могу предсказать, т.к возможна та самая пресловутая “poor implementation” протокола непосредственно на передатчике и в таком случае - уже в ваших руках продиагностировать это (прилагаемый VTX_Test как раз для этих нужд), поиграться с smartbauding(читал такие жалобы, где некоторые передатчики работают корректно на 9200, вместо 9600bps), засылаемыми и принимаемыми пакетами, чтобы заставить ваш передатчик заработать на протоколе, возможно придется записывать лишние байты после отсылки пакета, возможно - наоборот - только пакет без лишних байт. И да, я постарался детально рассказать об этих протоколах и разьяснить предоставляемый код, надеюсь это сэкономит чье-то время, потраченное на ознакомление с этими протоколами, их реализацией и особенностями.
Комментарии по коду:
Код - компиляция SoftwareSerialWithHalfDuplex (для реализации функционала порта UART) со вставками из CustomSoftwareSerial (для поддержки различных конфигураций UART и поддержки конкретно 8N2), использован код из ArduPilot и BetaFlight. Код достаточно комментирован для понимания, особенностей использования. Конечно можно его развить для отражения полной системы команд, но мне необходим был функционал переключения каналов и мощности.
Конкретно для ситуации с интересной особенностью реализации SA на TX5258, о которой я упоминал, используется define SMARTAUDIO_WRITE_ZEROBYTES_AT_THE_END.
Структура кода такова: SoftwareSerialWithHalfDuplex - реализация SoftwareSerial порта (реализовано на прерывании, не на таймере, работает не на всех пинах Ардуино, в комментарии к конструктору SoftwareSerialWithHalfDuplex упоминаются пины, которые можно использовать), VTXControl - конфигурирует в зависимости от параметров и режима (SA или Tramp) и использует этот порт. В VTXControl доступны 3 функции: updateParameters (получение текущих параметров VTX), setPower (для установки мощности), setChannel (для установки канала). Есть дополнительные setPowerInmW (для установки мощности в mW), setFrequency (для установки частоты, а не номера канала) - эти функции добавлены для удобства и для решения проблемы “где хранить параметры передатчика”, я ее так и не решил элегантно, приходится хранить параметры как в коде VTXControl, так и в управляющем коде, дань универсальности, но с дополнительными функциями, есть возможность хранить параметры передатчика в управляющем коде, а не в VTXControl. VTX_Tramp.h и VTX_SmartAudio.h содержат специфические для этих протоколов данные, описания, установки и процедуры. Прилагаемый Arduino-проект VTX_Test - для тестирования и диагностики передатчика на плате Arduino.
Параметры передатчика можно найти в VTXControl.cpp: powers, powers_v1, powers_v21, freqs. Возможно powers будет стоить поменять на параметры вашего передатчика, допустим добавить мощность 1000mW, но вот с powers_v1, powers_v21 - тут сложнее, т.к в этих массивах описаны хард-код данные, поддерживаемые версиями v1, v2.1 smartAudio, и собственно поэтому в AP не могут юзеры установить мощность выше 4-й, если протокол SmartAudio 1-й или 2.1 версии. Ну или, как я выше писал, использовать лайфхак: установить эту мощность на передатчике кнопкой, выловить ее значение командой updateParameters какое ее значение выдаст передатчик. Но возможно, что передатчик поддерживает версию 2, и в таком случае он будет работать уровнями(индексами) мощности-1,2, 3,4,5 и это упростит дело.
В VTXControl функции относящиеся к специфике SA начинаются с префикса sa_, трамповские - с tramp.
Игнорирование crc в протоколе SA устанавливается define SMARTAUDIO_IGNORE_CRC в VTX_SmartAudio.h
Так как SoftwareSerialWithHalfDuplex работает от прерываний, то длительные операции и использование функции delay (она запрещает прерывания) не рекомендованы. Поэтому испольуется функция waitForInMs, использующая delayMicroseconds (которая не запрещает прерывания, а использует пропуск тактов микроконтроллера). Эта функция необходима для ожидания ответа от VTX и ждет она время заданное в конструкторе VTXControl, responseTimeOut. Обычно ответ занимает в районе 200-400ms, максимум 1000(согласно оду BF/AP), поэтому этот параметр может быть индивидуальным для вашего передатчика.В VTX_Test использовалось значение в 1400ms, но это слишком много, как показала практика. Значения доводились и до 400ms и все работало прекрасно. Но время ожидание в моем случае было некритично. Поэтому даже 2000ms для получения уверенного ответа было приемлемым. Другое дело, когда такой режим ожидания используется при smartbauding - это уже слишком долго - используется несколько попыток достучаться до VTX, меняется в широком диапазоне baud rate - это и так занимает время. В этом случае конечно стоит уменьшать responseTimeOut.
В коде управления передатчиком введена диагностика ошибок (даже без режима детальной диагностики), и после отсылки команды/запроса, можно вызвать метод getErrors, для получения флагов ошибок, пример VTX_Test содержит метод PrintErrors, который разбирает флаги ошибок.
Конечно можно было бы ввести в функционал поддержку управлением PitMode и запросами температуры, но преследовалась цель “управление каналом и мощностью”, поэтому этот функционал не реализован.
Для включения детальной диагностики на VTXControl раскомментируйте #define VTXCDEBUG в VTXControl.h, для включения диагностики порта, раскомментируйте #define SSWHD_DEBUG в SoftwareSerialWithHalfDuplex.h