Path: blob/master/libraries/AP_CRSF/AP_CRSF_Protocol.h
9670 views
/*1* This file is free software: you can redistribute it and/or modify it2* under the terms of the GNU General Public License as published by the3* Free Software Foundation, either version 3 of the License, or4* (at your option) any later version.5*6* This file is distributed in the hope that it will be useful, but7* WITHOUT ANY WARRANTY; without even the implied warranty of8* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.9* See the GNU General Public License for more details.10*11* You should have received a copy of the GNU General Public License along12* with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16* Crossfire protocol definitions - shared between AP_RCProtocol_CRSF and AP_CRSF_Telem17* Crossfire constants provided by Team Black Sheep under terms of the 2-Clause BSD License18*/19#pragma once2021#include "AP_CRSF_config.h"2223#if AP_CRSF_ENABLED2425#include <stdint.h>26#include <AP_HAL/AP_HAL_Boards.h>2728#define CRSF_MAX_CHANNELS 24U // Maximum number of channels from crsf datastream29#define CRSF_FRAMELEN_MAX 64U // maximum possible framelength30#define CRSF_HEADER_LEN 2U // header length31#define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CRSF_HEADER_LEN) // maximum size of the frame length field in a packet3233class AP_CRSF_Protocol {34public:3536enum FrameType {37CRSF_FRAMETYPE_GPS = 0x02,38CRSF_FRAMETYPE_VARIO = 0x07,39CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,40CRSF_FRAMETYPE_BARO_VARIO = 0x09,41CRSF_FRAMETYPE_HEARTBEAT = 0x0B,42CRSF_FRAMETYPE_VTX = 0x0F,43CRSF_FRAMETYPE_VTX_TELEM = 0x10,44CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,45CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,46CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED = 0x17,47CRSF_FRAMETYPE_RC_CHANNELS_PACKED_11BIT = 0x18,48CRSF_FRAMETYPE_LINK_STATISTICS_RX = 0x1C,49CRSF_FRAMETYPE_LINK_STATISTICS_TX = 0x1D,50CRSF_FRAMETYPE_ATTITUDE = 0x1E,51CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,52// Extended Header Frames, range: 0x28 to 0x9653CRSF_FRAMETYPE_PARAM_DEVICE_PING = 0x28,54CRSF_FRAMETYPE_PARAM_DEVICE_INFO = 0x29,55CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,56CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,57CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,58CRSF_FRAMETYPE_COMMAND = 0x32,59// Custom Telemetry Frames 0x7F,0x8060CRSF_FRAMETYPE_AP_CUSTOM_TELEM_LEGACY = 0x7F, // as suggested by Remo Masina for fw < 4.0661CRSF_FRAMETYPE_AP_CUSTOM_TELEM = 0x80, // reserved for ArduPilot by TBS, requires fw >= 4.0662};6364// Command IDs for CRSF_FRAMETYPE_COMMAND65enum CommandID {66CRSF_COMMAND_FC = 0x01,67CRSF_COMMAND_BLUETOOTH = 0x03,68CRSF_COMMAND_OSD = 0x05,69CRSF_COMMAND_VTX = 0x08,70CRSF_COMMAND_LED = 0x09,71CRSF_COMMAND_GENERAL = 0x0A,72CRSF_COMMAND_RX = 0x10,73CRSF_COMMAND_ACK = 0xFF,74};7576enum DeviceAddress {77CRSF_ADDRESS_BROADCAST = 0x00,78CRSF_ADDRESS_USB = 0x10,79CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,80CRSF_ADDRESS_RESERVED1 = 0x8A,81CRSF_ADDRESS_PNP_PRO_CURRENT_SENSOR = 0xC0,82CRSF_ADDRESS_PNP_PRO_GPS = 0xC2,83CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,84CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,85CRSF_ADDRESS_RESERVED2 = 0xCA,86CRSF_ADDRESS_RACE_TAG = 0xCC,87CRSF_ADDRESS_VTX = 0xCE,88CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,89CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,90CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE91};9293// Commands for CRSF_COMMAND_GENERAL94enum CommandGeneral {95CRSF_COMMAND_GENERAL_CHILD_DEVICE_REQUEST = 0x04,96CRSF_COMMAND_GENERAL_CHILD_DEVICE_FRAME = 0x05,97CRSF_COMMAND_GENERAL_FIRMWARE_UPDATE_BOOTLOADER = 0x0A,98CRSF_COMMAND_GENERAL_FIRMWARE_UPDATE_ERASE = 0x0B,99CRSF_COMMAND_GENERAL_WRITE_SERIAL_NUMBER = 0x13,100CRSF_COMMAND_GENERAL_USER_ID = 0x15,101CRSF_COMMAND_GENERAL_SOFTWARE_PRODUCT_KEY = 0x60,102CRSF_COMMAND_GENERAL_CRSF_SPEED_PROPOSAL = 0x70, // proposed new CRSF port speed103CRSF_COMMAND_GENERAL_CRSF_SPEED_RESPONSE = 0x71, // response to the proposed CRSF port speed104};105106// Commands for CRSF_COMMAND_VTX107enum CommandVTX {108CRSF_COMMAND_VTX_CHANNEL = 0x01,109CRSF_COMMAND_VTX_FREQ = 0x02,110CRSF_COMMAND_VTX_POWER = 0x03,111CRSF_COMMAND_VTX_PITMODE = 0x04,112CRSF_COMMAND_VTX_PITMODE_POWERUP = 0x05,113CRSF_COMMAND_VTX_POWER_DBM = 0x08,114};115116// Commands for CRSF_COMMAND_RX117enum CommandRX {118CRSF_COMMAND_RX_BIND = 0x01,119CRSF_COMMAND_RX_CANCEL_BIND = 0x02,120CRSF_COMMAND_RX_SET_BIND_ID = 0x03,121};122123// SubType IDs for CRSF_FRAMETYPE_CUSTOM_TELEM124enum CustomTelemSubTypeID : uint8_t {125CRSF_AP_CUSTOM_TELEM_SINGLE_PACKET_PASSTHROUGH = 0xF0,126CRSF_AP_CUSTOM_TELEM_STATUS_TEXT = 0xF1,127CRSF_AP_CUSTOM_TELEM_MULTI_PACKET_PASSTHROUGH = 0xF2,128};129130enum class ProtocolType {131PROTOCOL_CRSF,132PROTOCOL_TRACER,133PROTOCOL_ELRS134};135136struct Frame {137uint8_t device_address;138uint8_t length;139uint8_t type;140uint8_t payload[CRSF_FRAME_PAYLOAD_MAX - 1]; // type is already accounted for141} PACKED;142143struct SubsetChannelsFrame {144#if __BYTE_ORDER__ != __ORDER_LITTLE_ENDIAN__145#error "Only supported on little-endian architectures"146#endif147uint8_t starting_channel:5; // which channel number is the first one in the frame148uint8_t res_configuration:2; // configuration for the RC data resolution (10 - 13 bits)149uint8_t digital_switch_flag:1; // configuration bit for digital channel150uint8_t channels[CRSF_FRAME_PAYLOAD_MAX - 2]; // payload less byte above151// uint16_t channel[]:res; // variable amount of channels (with variable resolution based152// on the res_configuration) based on the frame size153// uint16_t digital_switch_channel[]:10; // digital switch channel154} PACKED;155156struct LinkStatisticsTXFrame {157uint8_t rssi_db; // RSSI(dBm*-1)158uint8_t rssi_percent; // RSSI in percent159uint8_t link_quality; // Package success rate / Link quality ( % )160int8_t snr; // SNR(dB)161uint8_t rf_power_db; // rf power in dBm162uint8_t fps; // rf frames per second (fps / 10)163} PACKED;164165// CRSF_FRAMETYPE_HEARTBEAT166struct HeartbeatFrame {167uint8_t origin; // Device address168};169170// CRSF_FRAMETYPE_COMMAND171struct PACKED CommandFrame {172uint8_t destination;173uint8_t origin;174uint8_t command_id;175uint8_t payload[9]; // 8 maximum for LED command + crc8176};177178// CRSF_FRAMETYPE_PARAM_DEVICE_PING179struct PACKED ParameterPingFrame {180uint8_t destination;181uint8_t origin;182};183184// CRSF_FRAMETYPE_PARAM_DEVICE_INFO185struct PACKED ParameterDeviceInfoFrame {186uint8_t destination;187uint8_t origin;188uint8_t payload[58]; // largest possible frame is 60189};190191// get printable name for frame type (for debug)192static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0);193};194195#endif // AP_CRSF_ENABLED196197198