Протокол CRSF |
![]() |
Добавил(а) microsin | |||||||||||||||||||||||||||||||||
Это перевод документации с описанием протокола CRSF [1]. Этот протокол применяется для передачи данных управления квадрокоптерами по радиоканалу. Непонятные термины и сокращения см. в разделе Словарик. Функциональные возможности протокола CRSF: • Высокая скорость передачи данных с низкими задержками между RC - TX и RX - FC. Этот документ служит публичным "единым источником истины", поддерживаемым TBS [2], документируя протокол. Он служит справочным материалом для реализации CRSF-совместимых устройств, а также позволяет разработчикам, не связанным с TBS, озвучивать требования и предлагать расширения к существующим протоколам. Он также установит CRSF как наиболее широко внедренный современный протокол связи для устройств R/C. [Аппаратура CRSF] Single-Wire Half-Duplex UART. Эта обычно используемая конфигурация сигнала между RC и TX. RC в этом случае действует как master, и TX отвечает телеметрией, если он синхронизирован с кадрами RC, посылаемыми RC. RC должен посылать только один кадр с предварительно сконфигурированной или согласованной частотой, и должен переключить линию в состояние высокого сопротивления, и ждать ответа от TX. UART по умолчанию работает на на скорости 400 kbaud (baudrate) с форматом 8N1 (с инверсией или без) на уровнях TTL-логики 3.3V, однако также поддерживается 115.2 kbaud и более высокие скорости (1Mbaud, 2Mbaud), в зависимости от аппаратуры (см. 0x70 CRSF Protocol Speed Proposal). Рекомендуется, чтобы модули TX были сконфигурированы на на одинаковую скорость, или автоматически определять скорость передачи. Максимальная частота кадров (frame-rate) должна быть выбрана в зависимости от baudrate для возможности передачи кадров RC и TX максимальной длины (64 байта в одном кадре). Dual-Wire Full-Duplex UART. Эта конфигурация обычно используется на стороне летающей платформы. Два устройства соединяются друг с другом обычным линком UART (сигналы RXD и TXD, передающими данные дуплексом в обоих направлениях). В этой конфигурации поддерживается только не инвертированный (обычный) UART. UART по умолчанию работает на скорости 416666 baud, кадр 8N1 с уровнями между 3.0V и 3.3V, однако скорость может быть согласована на более высокую, чтобы реализовать ускоренную передачу данных и снизить задержки. Multi-master I2C (BST). (EOL) BST это шина I2C с несколькими главными устройствами (multi master I2C). Она работает с уровнями 3.3V на скорости 100kHz, используя 7-бит адресацию. Адреса устройства уже содержат бит R/W. Это означает, что адрес записи меньше адреса чтения на 1. Каждое устройство, поддерживающее BST, должно освободить SDA в любом случае, чтобы не блокировать шину. Рекомендуется мониторить heartbeat-сообщение и сбрасывать интерфейс, если произошел таймаут 1.5 сек. Необходимо поддерживать кадры общего вызова, которые в этом документе называются broadcast кадрами. [Структура кадра CRSF] Базовая структура каждого кадра одна и та же. Существует ряд типов кадров с расширенным заголовком, в котором будут стандартизированы первые несколько байт полезной нагрузки. Это требуется для маршрутизации кадров между несколькими устройствами, чтобы реализовать обмен данными точка-точка. Каждый кадр CRSF имеет длину не более 64 байта (включая байты Sync и CRC). Broadcast Frame
[Sync byte] [Frame Length] [Type] [Payload] [CRC] Extended Header Frame
Из чего состоит кадр: • Sync byte может быть одним из следующих (т. е. принимающее устройство должно ожидать любой из них): - Serial sync byte: 0xC8; • Frame length: количество байт в кадре, исключая байт Sync и Frame Length (в основном это полный размер кадра -2) - Broadcast Frame: Type + Payload + CRC • Type: тип кадра • Payload: полезная нагрузка (данные) Порядок байт многобайтных значений (endianness): Big endian (MSB) [6]. Размер кадра может превышать ожидаемый размер кадра для определенного типа. Это не должно быть причиной считать кадр некорректным. Приемник кадра должен просто игнорировать лишние поля. Возможно, что отправитель кадра поддерживает более новую версию протокола CRSF и отправляет некоторые дополнительные поля после известных полей. И наоборот: если в кадре имеются некоторые опциональные (не обязательные) поля, то иногда эти поля могут быть установлены как пустые (например, строка ASCIIZ нулевой длины), но иногда эти поля могут отсутствовать, и размер кадра может быть сокращен. Не пытайтесь читать поля за пределами полезной нагрузки кадра. Маршрутизация. Если в устройстве больше одного порта CRSF, то необходимо переслать все принятые кадры на другие порты. CRSF работает как звездообразная сеть с фиксированными адресными таблицами на каждом узле сети. Запрещается использовать любое циклическое соединение, так как оно будет бесконечно пересылать одно и то же сообщение. CRC. Контрольная сумма кадра вычисляется от Type и Payload (данные байт sync и frame length не включаются). Используется алгоритм CRC8 с полиномом x7+ x6+ x4+ x2+ x0 (0xD5) unsigned char crc8tab[256] = { 0x00, 0xD5, 0x7F, 0xAA, 0xFE, 0x2B, 0x81, 0x54, 0x29, 0xFC, 0x56, 0x83, 0xD7, 0x02, 0xA8, 0x7D, 0x52, 0x87, 0x2D, 0xF8, 0xAC, 0x79, 0xD3, 0x06, 0x7B, 0xAE, 0x04, 0xD1, 0x85, 0x50, 0xFA, 0x2F, 0xA4, 0x71, 0xDB, 0x0E, 0x5A, 0x8F, 0x25, 0xF0, 0x8D, 0x58, 0xF2, 0x27, 0x73, 0xA6, 0x0C, 0xD9, 0xF6, 0x23, 0x89, 0x5C, 0x08, 0xDD, 0x77, 0xA2, 0xDF, 0x0A, 0xA0, 0x75, 0x21, 0xF4, 0x5E, 0x8B, 0x9D, 0x48, 0xE2, 0x37, 0x63, 0xB6, 0x1C, 0xC9, 0xB4, 0x61, 0xCB, 0x1E, 0x4A, 0x9F, 0x35, 0xE0, 0xCF, 0x1A, 0xB0, 0x65, 0x31, 0xE4, 0x4E, 0x9B, 0xE6, 0x33, 0x99, 0x4C, 0x18, 0xCD, 0x67, 0xB2, 0x39, 0xEC, 0x46, 0x93, 0xC7, 0x12, 0xB8, 0x6D, 0x10, 0xC5, 0x6F, 0xBA, 0xEE, 0x3B, 0x91, 0x44, 0x6B, 0xBE, 0x14, 0xC1, 0x95, 0x40, 0xEA, 0x3F, 0x42, 0x97, 0x3D, 0xE8, 0xBC, 0x69, 0xC3, 0x16, 0xEF, 0x3A, 0x90, 0x45, 0x11, 0xC4, 0x6E, 0xBB, 0xC6, 0x13, 0xB9, 0x6C, 0x38, 0xED, 0x47, 0x92, 0xBD, 0x68, 0xC2, 0x17, 0x43, 0x96, 0x3C, 0xE9, 0x94, 0x41, 0xEB, 0x3E, 0x6A, 0xBF, 0x15, 0xC0, 0x4B, 0x9E, 0x34, 0xE1, 0xB5, 0x60, 0xCA, 0x1F, 0x62, 0xB7, 0x1D, 0xC8, 0x9C, 0x49, 0xE3, 0x36, 0x19, 0xCC, 0x66, 0xB3, 0xE7, 0x32, 0x98, 0x4D, 0x30, 0xE5, 0x4F, 0x9A, 0xCE, 0x1B, 0xB1, 0x64, 0x72, 0xA7, 0x0D, 0xD8, 0x8C, 0x59, 0xF3, 0x26, 0x5B, 0x8E, 0x24, 0xF1, 0xA5, 0x70, 0xDA, 0x0F, 0x20, 0xF5, 0x5F, 0x8A, 0xDE, 0x0B, 0xA1, 0x74, 0x09, 0xDC, 0x76, 0xA3, 0xF7, 0x22, 0x88, 0x5D, 0xD6, 0x03, 0xA9, 0x7C, 0x28, 0xFD, 0x57, 0x82, 0xFF, 0x2A, 0x80, 0x55, 0x01, 0xD4, 0x7E, 0xAB, 0x84, 0x51, 0xFB, 0x2E, 0x7A, 0xAF, 0x05, 0xD0, 0xAD, 0x78, 0xD2, 0x07, 0x53, 0x86, 0x2C, 0xF9}; _crc_tab = [ 0x00, 0xD5, 0x7F, 0xAA, 0xFE, 0x2B, 0x81, 0x54, 0x29, 0xFC, 0x56, 0x83, 0xD7, 0x02, 0xA8, 0x7D, 0x52, 0x87, 0x2D, 0xF8, 0xAC, 0x79, 0xD3, 0x06, 0x7B, 0xAE, 0x04, 0xD1, 0x85, 0x50, 0xFA, 0x2F, 0xA4, 0x71, 0xDB, 0x0E, 0x5A, 0x8F, 0x25, 0xF0, 0x8D, 0x58, 0xF2, 0x27, 0x73, 0xA6, 0x0C, 0xD9, 0xF6, 0x23, 0x89, 0x5C, 0x08, 0xDD, 0x77, 0xA2, 0xDF, 0x0A, 0xA0, 0x75, 0x21, 0xF4, 0x5E, 0x8B, 0x9D, 0x48, 0xE2, 0x37, 0x63, 0xB6, 0x1C, 0xC9, 0xB4, 0x61, 0xCB, 0x1E, 0x4A, 0x9F, 0x35, 0xE0, 0xCF, 0x1A, 0xB0, 0x65, 0x31, 0xE4, 0x4E, 0x9B, 0xE6, 0x33, 0x99, 0x4C, 0x18, 0xCD, 0x67, 0xB2, 0x39, 0xEC, 0x46, 0x93, 0xC7, 0x12, 0xB8, 0x6D, 0x10, 0xC5, 0x6F, 0xBA, 0xEE, 0x3B, 0x91, 0x44, 0x6B, 0xBE, 0x14, 0xC1, 0x95, 0x40, 0xEA, 0x3F, 0x42, 0x97, 0x3D, 0xE8, 0xBC, 0x69, 0xC3, 0x16, 0xEF, 0x3A, 0x90, 0x45, 0x11, 0xC4, 0x6E, 0xBB, 0xC6, 0x13, 0xB9, 0x6C, 0x38, 0xED, 0x47, 0x92, 0xBD, 0x68, 0xC2, 0x17, 0x43, 0x96, 0x3C, 0xE9, 0x94, 0x41, 0xEB, 0x3E, 0x6A, 0xBF, 0x15, 0xC0, 0x4B, 0x9E, 0x34, 0xE1, 0xB5, 0x60, 0xCA, 0x1F, 0x62, 0xB7, 0x1D, 0xC8, 0x9C, 0x49, 0xE3, 0x36, 0x19, 0xCC, 0x66, 0xB3, 0xE7, 0x32, 0x98, 0x4D, 0x30, 0xE5, 0x4F, 0x9A, 0xCE, 0x1B, 0xB1, 0x64, 0x72, 0xA7, 0x0D, 0xD8, 0x8C, 0x59, 0xF3, 0x26, 0x5B, 0x8E, 0x24, 0xF1, 0xA5, 0x70, 0xDA, 0x0F, 0x20, 0xF5, 0x5F, 0x8A, 0xDE, 0x0B, 0xA1, 0x74, 0x09, 0xDC, 0x76, 0xA3, 0xF7, 0x22, 0x88, 0x5D, 0xD6, 0x03, 0xA9, 0x7C, 0x28, 0xFD, 0x57, 0x82, 0xFF, 0x2A, 0x80, 0x55, 0x01, 0xD4, 0x7E, 0xAB, 0x84, 0x51, 0xFB, 0x2E, 0x7A, 0xAF, 0x05, 0xD0, 0xAD, 0x78, 0xD2, 0x07, 0x53, 0x86, 0x2C, 0xF9, ] [Адреса устройств] 0x00 Broadcast address (широковещательный адрес) [Broadcast Frame Types] Это широковещательные типы кадра, у которых тип кадра меньше 0x27. У них простой (короткий) заголовок. 0x02 GPS Координаты, полученные от GPS. int32_t latitude; // degree / 10`000`000 int32_t longitude; // degree / 10`000`000 uint16_t groundspeed; // km/h / 100 uint16_t heading; // degree / 100 uint16_t altitude; // meter - 1000m offset uint8_t satellites; // сколько есть видимых спутников 0x03 GPS Time Этот кадр требуется для синхронизации по импульсу времени ublox [3]. Максимальное смещение времени +/- 10 мс. int16_t year; uint8_t month; uint8_t day; uint8_t hour; uint8_t minute; uint8_t second; uint16_t millisecond; 0x06 GPS Extended uint8_t fix_type; // Текущее качество фиксации GPS int16_t n_speed; // Скорость в сторону севера, north [см/сек] (в сторону севера // n_speed положительное, в сторону юга отрицательное) int16_t e_speed; // Скорость в сторону востока, east [см/сек] (в сторону востока // e_speed положительное, в сторону запада отрицательное) int16_t v_speed; // Вертикальная скорость [см/сек] (вверх v_speed положительное) int16_t h_speed_acc; // Точность горизонтальной скорости, см/сек int16_t track_acc; // Точность курса, градусы в масштабе 1e-1 умножить на 10 int16_t alt_ellipsoid; // Высота в метрах над эллипсоидом GPS (не MSL) int16_t h_acc; // Горизонтальная точность в см int16_t v_acc; // Вертикальная точность в см uint8_t reserved; uint8_t hDOP; // Горизонтальное снижение точности, безразмерные единицы .1. uint8_t vDOP; // Вертикальное снижение точности, безразмерные единицы .1. 0x07 Variometer Sensor int16_t v_speed; // Вертикальная скорость, см/сек 0x09 Barometric Altitude & Vertical Speed Этот кадр позволяет отправить высоту и вертикальную скорость более эффективным в плане количества бит способом. Он позволяет комбинировать в 3 байтах высоту дециметровой точности с 32 км диапазоном и 3 см/сек точностью вертикальной скорости в диапазоне 25 м/сек. uint16_t altitude_packed; // Высота выше стартовой (калиброванной) точки // См. описание далее. int8_t vertical_speed_packed; // Вертикальная скорость. См. описание далее. Значение высоты зависит от MSB (бит 15): MSB = 0: высота в дециметрах - 10000 dm смещение (так что 0 представляет -1000 м; 10000 представляет 0 м (стартовая высота); 0x7fff представляет 2276.7 м); int32_t get_altitude_dm(uint16_t packed){ return (packed & 0x8000) ? (packed & 0x7fff) * 10 : (packed - 10000); } Вертикальная скорость, представленная в см/сек, с логарифмической шкалой. Функции её распаковки и упаковки: const int Kl = 100; // константа линейности; Такие константы дают диапазон ±2500 см/сек и точность 3 см/сек на низкой скорости и 70 см/сек точность на скорости порядка 25 м/сек; 0x0B Heartbeat int16_t origin_address; // Адрес устройства-источника 0x0F Discontinued 0x10 VTX Telemetry uint8_t origin_address; uint8_t power_dBm; // Мощность VTX в dBm uint16_t frequency_MHz; // Частота VTX в МГц uint8_t pit_mode:1; // 0=Off, 1=On uint8_t pitmode_control:2; // 0=Off, 1=On, 2=Switch, 3=Failsafe uint8_t pitmode_switch:4; // 0=Ch5, 1=Ch5 Inv, ... , 15=Ch12 Inv 0x14 Link Statistics Uplink это соединение от земли до UAV, а downlink в обратном направлении. uint8_t up_rssi_ant1; // Uplink RSSI Antenna 1 (dBm * -1) uint8_t up_rssi_ant2; // Uplink RSSI Antenna 2 (dBm * -1) uint8_t up_link_quality; // Uplink Package success rate / Link quality (%) int8_t up_snr; // Uplink SNR (dB) uint8_t active_antenna; // Номер текущей лучшей антенны uint8_t rf_profile; // enum {4fps = 0 , 50fps, 150fps} uint8_t up_rf_power; // enum {0mW = 0, 10mW, 25mW, 100mW, // 500mW, 1000mW, 2000mW, 250mW, 50mW} uint8_t down_rssi; // Downlink RSSI (dBm * -1) uint8_t down_link_quality; // Downlink Package success rate / Link quality (%) int8_t down_snr; // Downlink SNR (dB) 0x16 RC Channels Packed Payload 16 каналов управления, упакованные в 22 байта. В случае Failsafe этот кадр больше не будет посылаться (когда тип failsafe установлен в "cut"). Рекомендуется подождать 1 секунду перед запуском подпрограммы FC failsafe. #define TICKS_TO_US(x) ((x - 992) * 5 / 8 + 1500) 0x17 Subset RC Channels Packed Предупреждение: этот кадр не рекомендуется для реализации. Выполняется ревизия. // Пример вычисления значений rc в значения канала: 0x18 RC Channels Packed 11-bits (не используется) То же самое что и 0x16, но с таким же стилем преобразования, как у 0x17. 0x19 - 0x1B Reserved Crossfire 0x1C Link Statistics RX uint8_t rssi_db; // RSSI (dBm * -1) uint8_t rssi_percent; // RSSI в процентах uint8_t link_quality; // Package success rate / Link quality (%) int8_t snr; // SNR (dB) uint8_t rf_power_db; // мощность радиоканала в dBm 0x1D Link Statistics TX uint8_t rssi_db; // RSSI (dBm * -1) uint8_t rssi_percent; // RSSI в процентах uint8_t link_quality; // Package success rate / Link quality (%) int8_t snr; // SNR (dB) uint8_t rf_power_db; // мощность радиоканала в dBm uint8_t fps; // количество кадров в секунду (fps / 10) 0x1E Attitude Предупреждение: значения угла должны быть в диапазоне -180° +180°! int16_t pitch; // Pitch angle (LSB = 100 µrad) int16_t roll; // Roll angle (LSB = 100 µrad) int16_t yaw; // Yaw angle (LSB = 100 µrad) 0x1F MAVLink FC int16_t airspeed; uint8_t base_mode; // флаги режима устройства, определенные // в MAV_MODE_FLAG enum uint32_t custom_mode; // флаги, относящиеся к автопилоту uint8_t autopilot_type; // тип FC; определен в MAV_AUTOPILOT enum uint8_t firmware_type; // тип устройства; определен в MAV_TYPE enum Официальная документация MAVLink: MAV_MODE_FLAG enum 0x21 Flight Mode char[] Flight mode // ASCIIZ-строка 0x22 ESP_NOW Messages uint8_t VAL1; // Используется для положения сиденья пилота uint8_t VAL2; // Используется для текущего круга пилотов char VAL3[15]; // 15 символов для текущего/разделенного времени круга char VAL4[15]; // 15 символов для текущего/разделенного времени круга char FREE_TEXT[20]; // Произвольный текст из 20 символов в нижней части // экрана 0x27 Reserved [Extended Frame Types] Кадры типа 0x28 и выше (если явно не указано нечто иное) имеют расширенный заголовок (extended header), с полями точки назначения (destination) и источника (origin). 0x28 Parameter Ping Devices Хост может посылать ping на указанное устройство (адрес узла назначения устройства) или на все устройства (адрес узла назначения 0x00 Broadcast address), и они ответят кадром информации об устройстве (Parameter device information). У кадра нет полезной нагрузки. 0x29 Parameter Device Information char[] Device_name; // ASCIIZ-строка uint32_t Serial_number; uint32_t Hardware_ID; uint32_t Firmware_ID; uint8_t Parameters_total; // общее количество параметров uint8_t Parameter_version_number; Блоки пакета. Максимальный размер кадр CRSF равен 64 байта (включая байт sync и CRC). Хост всегда должен читать (0x2C Parameter settings (read)) блок номер 0 по умолчанию. Если параметр чтения (0x2B Parameter settings (entry)) укладывается в максимальный размер, то он ответит блоками оставшимися 0 внутри кадра параметра. Иначе он будет посылать столько блоков, сколько осталось фрагментов для чтения. Пример цепочки кадров Parameter settings (0x2B и 0x2C): Блок полезной нагрузки кадров имеет следующую структуру: uint8_t Parameter_number; // начинается от 0 0x2B Parameter Settings (Entry) Так устройство (адрес узла) может совместно использовать параметр с другим устройством. См. выше "Блоки пакета". Замечание: если Data_type_payload_chunk ≤ 56, то может быть отправлен 1 кадр, иначе полезная нагрузка будет передаваться блоками в 2 или большего количества кадров. uint8_t Sync_byte; // 0xc8 uint8_t Frame_length; uint8_t Frame_type; // 0x2b = Parameter settings (entry) uint8_t Destination_address; // 0xea = RC uint8_t Origin_address; // 0xee = TX uint8_t Parameter_number; // начинается от 0 uint8_t Parameter_chunks_remaining; // количество оставшихся блоков { Data_type_payload_chunk; // см. ниже полезную нагрузку для каждого типа } uint8_t CRC_8; // Frame CRC (см. описание CRC) Определение типа параметров и бит скрытости. Тип параметра имеет разрядность 8 бит. Бит 7 показывает скрытость параметра (1 = скрытый / 0 = видимый). Это дает возможность динамически показывать и скрывать параметры в зависимости от других параметров. Биты 6 .. 0 хранят информацию о типе параметра (перечисление data_type). enum data_type { UINT8 = 0, // обсуждается INT8 = 1, // обсуждается UINT16 = 2, // обсуждается INT16 = 3, // обсуждается UINT32 = 4, // обсуждается INT32 = 5, // обсуждается FLOAT = 8, TEXT_SELECTION = 9, STRING = 10, FOLDER = 11, INFO = 12, COMMAND = 13, OUT_OF_RANGE = 127 } OUT_OF_RANGE. Этот тип будет отправлен, если будет запрошен номер параметра из диапазона параметров устройства. Он также будет отправлен в качестве последнего параметра, чтобы хост знал конец списка параметров в списке Parameters settings (запрос чтения). UINT8, INT8, UINT16, INT16, UINT32, INT32. Предлагается к исключению. А настоящее время эти типы реализованы через тип FLOAT, который более общий. FLOAT. Value, min, max и default отправляются как INT32. Значение Decimal_point указывает, сколько цифр значения находится за десятичной точкой. Step_size это рекомендуемый инкремент или декремент для изменения Value. uint8_t Parent_folder; // номер параметра родительской папки, // 0 означает корневую (root) папку enum data_type Data_type; // 0x08 = float char[] Name; // ASCIIZ строка int32_t Value; int32_t Min; int32_t Max; int32_t Default; uint8_t Decimal_point; int32_t Step_size; char[] Unit; // ASCIIZ строка TEXT_SELECTION. Часть значения этой записи разделена на две части. Первая это массив символов со всеми возможными значениями в текстовом формате. Они разделены символом точки с запятой (;), и массив завершается null-символом. Вторая часть это переменная uint8_t с текущим значением. Значения min, max и default представлены как числа uint8_t, где 0 представляет первый текст. Для изменения этого параметра только uint8_t value должно быть отправлено для нового значения. Полезная нагрузка Text Selection: uint8_t Parent folder; // номер параметра родительской папки, // 0 означает корневую (root) папку enum data_type Data type; // 0x09 = выбор текста char[] Name; // ASCIIZ строка char[] Options; // ASCIIZ строка, представляющая собой // список, где параметры отделяются // символом точки с запятой uint8_t Value; uint8_t Min; uint8_t Max; uint8_t Default; char[] Unit; // ASCIIZ строка STRING. Этот тип предназначен для модификации текста. Будет передаваться только текущий текст. Для этого типа не посылаются min, max и default записи. Полезная нагрузка String: uint8_t Parent_folder; // номер параметра родительской папки, // 0 означает корневую (root) папку enum data_type Data_type; // 0x0a = string char[] Name; // ASCIIZ строка char[] Value; // ASCIIZ строка uint8_t String_max_length; // только для типа string FOLDER. Папка используется для улучшения структуры параметров. Каждый параметр имеет родительскую запись, где параметр может ссылаться на folder родителя. Дополнительно folder предоставит список его потомков и добавит имя folder. Конец списка маркируется байтом 0xFF. Список будет содержаться номер параметра потомка. Полезная нагрузка Folder: uint8_t Parent_folder; // номер параметра родительской папки, // 0 означает корневую (root) папку enum data_type Data_type; // 0x0b = folder char[] Name; // ASCIIZ строка uint8_t[] List_of_children; // записью 0xFF помечается конец списка INFO. Значение в виде ASCIIZ-строки. То же самое, что и STRING, за исключением того, что запись INFO не может быть изменена и не включает максимальную длину. Полезная нагрузка Info: uint8_t Parent_folder; // номер параметра родительской папки, // 0 означает корневую (root) папку enum data_type Data_type; // 0x0c = info char[] Name; // ASCIIZ строка char[] Info; // ASCIIZ строка COMMAND. С типом команды хост может запустить/выполнить на устройстве функцию. Это может быть что угодно: привязка канала (link bind crossfire), калибровка гироскопа/акселерометра, и т. п. Статус по умолчанию устройства READY. Как только хост захотел выполнить функцию, он записывает параметр со статусом START. В зависимости от функции на устройстве оно переключается в статус PROGRESS, CONFIRMATION_NEEDED или READY. Когда устройство посылает хосту статус CONFIRMATION_NEEDED, отобразится бокс с выбором подтверждения ("confirm") или отмены ("cancel"). Если пользователь выберет что-то из этого, то оно будет передано на устройство, и функция проложит выполняться. В полем Info устройство может послать дополнительную информацию на хост. Если хост посылает статус POLL, то он этим заставит устройство послать обновленный статус 0x2B Parameter settings (entry). Полезная нагрузка Command: struct { uint8_t Parent_folder; // номер параметра родительской папки, // 0 означает корневую (root) папку enum data_type Data_type; // 0x0d = command char[] Name; // ASCIIZ строка enum cmd_status Status; // uint8_t uint8_t Timeout; // ms * 100 char[] Info; // ASCIIZ строка } Пример цепочки Command: 0x2C Parameter Settings (Read) Запрос определенного параметра. Эта команда предназначена для повторного запроса параметра/блока, который не прошел через линк. uint8_t Parameter_number; uint8_t Parameter_chunk_number; // номер блока для запроса, // начинающийся с 0 0x2D Parameter Value (Write) Эта команда для переназначения параметра. Узел назначения (destination node) для проверки ответит кадром значения параметра (Parameter value frame), отправленным по адресу узла источника (origin node). uint8_t Parameter_number; Data; // размер зависит от типа данных Замечание: размер зависит от типа данных, иначе эта запись не посылается, например: • Для TEXT_SELECTION - размер 1; 0x32 Direct Commands Кадр Command: uint8_t Command_ID; uint8_t[] Payload; // зависит от Command ID uint8_t Command_CRC8; // 8-битный CRC POLYNOM = 0xBA Кадр команды защищен дополнительно вычисленной CRC в конце её полезной нагрузки. CRC включает тип кадра (байт 0x32), Destination, Origin, Command ID и Payload каждого Command Frame. Реализация Command_CRC8 с полиномом = x7+ x5+ x4+ x3+ x1 (0xBA) Замечание: полином отличается от основной CRC кадра CRSF. Command CRC не исключает CRC в конце каждого кадра CRSF. Вам также понадобится включить CRC в конец для полного кадра. unsigned char command_crc8tab[256] = { 0x00, 0xBA, 0xCE, 0x74, 0x26, 0x9C, 0xE8, 0x52, 0x4C, 0xF6, 0x82, 0x38, 0x6A, 0xD0, 0xA4, 0x1E, 0x98, 0x22, 0x56, 0xEC, 0xBE, 0x04, 0x70, 0xCA, 0xD4, 0x6E, 0x1A, 0xA0, 0xF2, 0x48, 0x3C, 0x86, 0x8A, 0x30, 0x44, 0xFE, 0xAC, 0x16, 0x62, 0xD8, 0xC6, 0x7C, 0x08, 0xB2, 0xE0, 0x5A, 0x2E, 0x94, 0x12, 0xA8, 0xDC, 0x66, 0x34, 0x8E, 0xFA, 0x40, 0x5E, 0xE4, 0x90, 0x2A, 0x78, 0xC2, 0xB6, 0x0C, 0xAE, 0x14, 0x60, 0xDA, 0x88, 0x32, 0x46, 0xFC, 0xE2, 0x58, 0x2C, 0x96, 0xC4, 0x7E, 0x0A, 0xB0, 0x36, 0x8C, 0xF8, 0x42, 0x10, 0xAA, 0xDE, 0x64, 0x7A, 0xC0, 0xB4, 0x0E, 0x5C, 0xE6, 0x92, 0x28, 0x24, 0x9E, 0xEA, 0x50, 0x02, 0xB8, 0xCC, 0x76, 0x68, 0xD2, 0xA6, 0x1C, 0x4E, 0xF4, 0x80, 0x3A, 0xBC, 0x06, 0x72, 0xC8, 0x9A, 0x20, 0x54, 0xEE, 0xF0, 0x4A, 0x3E, 0x84, 0xD6, 0x6C, 0x18, 0xA2, 0xE6, 0x5C, 0x28, 0x92, 0xC0, 0x7A, 0x0E, 0xB4, 0xAA, 0x10, 0x64, 0xDE, 0x8C, 0x36, 0x42, 0xF8, 0x7E, 0xC4, 0xB0, 0x0A, 0x58, 0xE2, 0x96, 0x2C, 0x32, 0x88, 0xFC, 0x46, 0x14, 0xAE, 0xDA, 0x60, 0x6C, 0xD6, 0xA2, 0x18, 0x4A, 0xF0, 0x84, 0x3E, 0x20, 0x9A, 0xEE, 0x54, 0x06, 0xBC, 0xC8, 0x72, 0xF4, 0x4E, 0x3A, 0x80, 0xD2, 0x68, 0x1C, 0xA6, 0xB8, 0x02, 0x76, 0xCC, 0x9E, 0x24, 0x50, 0xEA, 0x48, 0xF2, 0x86, 0x3C, 0x6E, 0xD4, 0xA0, 0x1A, 0x04, 0xBE, 0xCA, 0x70, 0x22, 0x98, 0xEC, 0x56, 0xD0, 0x6A, 0x1E, 0xA4, 0xF6, 0x4C, 0x38, 0x82, 0x9C, 0x26, 0x52, 0xE8, 0xBA, 0x00, 0x74, 0xCE, 0xC2, 0x78, 0x0C, 0xB6, 0xE4, 0x5E, 0x2A, 0x90, 0x8E, 0x34, 0x40, 0xFA, 0xA8, 0x12, 0x66, 0xDC, 0x5A, 0xE0, 0x94, 0x2E, 0x7C, 0xC6, 0xB2, 0x08, 0x16, 0xAC, 0xD8, 0x62, 0x30, 0x8A, 0xFE, 0x44}; 0x32.0xFF Command ACK uint8_t Command_ID; uint8_t SubCommand_ID; uint8_t Action; // 1 означает, что target уже предпринимает действие // 0 означает некорректную команду 0 или отсутствие // функции в этой команде uint8_t[] или char[] Information; // ASCIIZ-строка 0x32.0x01 FC Commands - 0x01 Force Disarm 0x32.0x03 Bluetooth Command - 0x01 Reset 0x32.0x05 OSD Commands - 0x01 Send Buttons: 0x32.0x08 VTX Commands - 0x01 DISCONTINUED VTX Change Channel 0x32.0x09 LED - 0x01 Установка в умолчание (откат к специфическим для target настройкам) - 0x04 - 0x61 зарезервировано 0x32.0x10 Crossfire - 0x01 Установка приемника в режим привязки (bind mode) 0x32.0x12 Зарезервировано 0x32.0x20 Flow Control Frame Устройство может ограничить скорость данных или подписаться на определенный кадр. - 0x01 Subscribe (подписка) 0x32.0x22 Screen Command Для всех устройств, у которых есть LCD Screen. 0x32.0x22.0x01 Pop-up Message Start char[] Header; // ASCIIZ-строка char[] Info message; // ASCIIZ-строка uint8_t Max_timeout_interval; // Время в секундах bool Close_button_option; struct // не обязательное поле. Если его первый // байт null (selectionText пуст), // то это длиной только 1 байт (null). { char[] selectionText; // ASCIIZ-строка. Если пусто, // то другие поля не существуют. uint8_t value; uint8_t minValue; uint8_t maxValue; uint8_t defaultValue; char[] unit; // ASCIIZ-строка единицы измерения } add_data; // дополнительные данные для отображения // (например процент). char[] possible_values; // необязательное поле. Это массив // символов любых возможных ответов // значений в текстовом формате, разделенные // символом точки с запятой (;), и массив // заканчивается null. Замечание: необязательные поля могут либо начинаться на null, либо даже не умещаться в кадр. Проанализируйте размер кадра и не считывайте необязательные поля за пределами полезной нагрузки кадра. 0x32.0x22.0x02 Selection Return Value uint8_t value; bool response; // true(Process)/false(Cancel) 0x32.0x22.0x03 Зарезервировано 0x32.0x22.0x04 Зарезервировано 0x34 Logging Этот кадр имеет простой (короткий) заголовок. Используется только для целей отладки. uint16_t logtype; uint32_t timestamp; uint32_t para1; 0x36 Зарезервировано 0x38 Зарезервировано 0x3A - Remote Related Frames 0x3A.0x01 - 0x3A.0x09 - Зарезервировано 0x3A.0x10 Timing Correction (CRSF Shot) Наподобие "RC-sync"; наподобие "timing correction frame" (в EdgeTX). uint32_t update_interval; // LSB = 100ns int32 offset; // LSB = 100ns, положительные значения // означают, что данные пришли слишком // рано, отрицательные - слишком поздно. Несмотря на то, что значения имеют разрешающую способность 100 нс, по крайней мере в EdgeTX это округляется до 1 мкс разрешающей способности 16-битных значений по прибытии. 0x3C Game - 0x01 Add points 0x3E Зарезервировано 0x40 Зарезервировано 0x78 - 0x79 Зарезервировано KISSFC 0x7A MSP Request / 0x7B Response 0x7A • Кадр CRSF, который обертывает запрос MSP ( $M< или $X< ) 0x7B • Кадр CRSF, который обертывает ответ MSP ( $M>, $X>, $M!, $X! ) Кадр MSP, упакованный в полезную нагрузку CRSF Payload packing: • У кадра MSP вырезается заголовок ($ + M/X + [/]/!) и CRC - биты 0-3 представляют циклический номер кадра CRSF; • Размер блока MSP-body вычисляется от размера кадра CRSF. Но размер MSP-body должен быть проанализирован из самого MSP-body (в отношении версии MSP и Jumbo-frame). 0x7F ArduPilot Legacy Reserved 0x80 ArduPilot Reserved Passthrough Frame Кадр широковещания CRSF (CRSF broadcast frame), который обертывает "сквозной" пакет ArduPilot. Сквозные пакеты имеют три разновидности: • Одиночный кадр пакета, используемый для быстрых линков, где один сквозной кадр телеметрии возвращается для каждого кадра RC uint8_t sub_type = 0xF0; uint16_t appid; uint32_t data; • Multi-packet кадр, используемый на медленных линках - упаковывается до 9 сквозных кадров телеметрии в возврат из каждого кадра RC uint8_t sub_type = 0xF2; uint8_t size; struct PassthroughTelemetryPacket { uint16_t appid; uint32_t data; } packets[9]; • Status text frame (кадр текста статуса) uint8_t sub_type = 0xF1; uint8_t severity; char text[50]; // (ASCIIZ-строка) 0x81, 0x82 Зарезервировано mLRS Кадры широковещания 0x80 и 0x81 устанавливают коммуникацию модулей mLRS TX со скриптами mLRS Configuration Lua, запущенными на например EdgeTx и OpenTx RC. Они инкапсулируют сообщения протокола mLRS 'mBridge' в кадрах CRSF. Протокол позволяет устанавливать параметры и другой функционал, но особенно также передает метаданные, которые необходимы для параметров модели mLRS, предоставляя для пользователя различную информацию, управления версией, и фичи, специфичные для системы линка mLRS. 0x80: Коммуникация из Lua script/RC до модуля TX. Формат кадра:\
Два байта 0x4F, 0x57 это синхробайты протокола mBridge. 0x81: Коммуникация из модуля TX до Lua script/RC. Формат кадра:
Frame Length и CRC соответствуют спецификации CRSF, показанной выше. Протокол mBridge довольно сложен, поскольку служит mLRS для различных дополнительных целей помимо связи со сценарием конфигурации Lua. Домашняя страничка проекта mLRS опубликована на GitHub [4]. См. также [5]. 0xAA CRSF MAVLink Envelope • Конверт CRSF MAVLink разработан для передачи протокола MAVLink через роутеры CRSF. Он поддерживает кадры MAVLink2 и MAVLink1. Поскольку кадры MAVLink обычно намного длиннее, чем кадры CRSF (281 байт для MAVLink2 против 64 байт для CRSF), MAVLink кадры будут разбиты на блоки. • Обратите внимание, что кодирование / декодирование правильного количества блоков при записи / чтении конвертов MAVLink должно обрабатываться пользователем для обеспечения целостности данных. uint8_t total_chunks : 4; // общее количество блоков uint8_t current_chunk : 4; // номер текущего блока uint8_t data_size; // размер данных (максимум 58) uint8_t data[]; // массив данных (максимум 58 байт) Получается структура кадра CRSF:
0xAC CRSF MAVLink System Status Sensor • Кадр CRSF для упаковки информации об упаковке статуса датчика MAVLink FC. uint32_t sensor_present; uint32_t sensor_enabled; uint32_t sensor_health; CRSF двоичный протокол на основе кадров для радиоуправляемых устройств. EOL End of Life, продуктовая линейка, которая больше не выпускается. FC Flight Controller, контроллер управления моделью (например квадрокоптер). FPV First Person View, вид от первого лица. Подразумевается управление моделями, где установлена видеокамера, передающая изображение окружающей обстановки оператору. MSP Message Send Protocol, протокол прикладного уровня, используемый для отправки коротких сообщений между узлами в сети. Первоначальная версия протокола была опубликована в 1990 году (из Википедии). RC, R/C Remote Control: подразумевается пульт управления моделью (обычно по радиоканалу). RSSI Received Signal Strength Indicator, показатель уровня принимаемого сигнала. RX Receiver, приемник (который также является обычно трансивером). Может быть в виде отдельного устройства, или встроенным в FC или VTX. SNR Signal-to-Noise Ratio, соотношение сигнал/шум. TBS Team BlackSheep [2]. TX Transmitter, передатчик (который фактически трансивер). Обычно это часть (внешняя или встроенная в виде радиомодуля) пульта RC. UAV Unmanned Aerial Vehicle, беспилотник. VRX Video Receiver, приемник видеосигнала. VTX Video Transmitter, передатчик видеосигнала. [Ссылки] 1. CRSF Protocol. |