AP_CRSF: add shared CRSF protocol types

Add AP_CRSF_Protocol class with shared enums and structures that will
be used by both AP_RCProtocol_CRSF and AP_CRSF_Telem.

Includes:
- FrameType, CommandID, DeviceAddress, CommandGeneral, CommandVTX,
  CommandRX, CustomTelemSubTypeID, ProtocolType enums
- Frame, SubsetChannelsFrame, LinkStatisticsTXFrame structs
- HeartbeatFrame, CommandFrame, ParameterPingFrame,
  ParameterDeviceInfoFrame structs
- CRSF_MAX_CHANNELS, CRSF_FRAMELEN_MAX, CRSF_HEADER_LEN,
  CRSF_FRAME_PAYLOAD_MAX defines
- get_frame_type() debug helper method
This commit is contained in:
Andy Piper
2026-01-28 11:22:52 +00:00
parent 1fe63b5484
commit 8ee5638839
3 changed files with 295 additions and 0 deletions

View File

@@ -0,0 +1,77 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include "AP_CRSF_Protocol.h"
#if AP_CRSF_ENABLED
// get printable name for frame type (for debug)
const char* AP_CRSF_Protocol::get_frame_type(uint8_t byte, uint8_t subtype)
{
switch (byte) {
case CRSF_FRAMETYPE_GPS:
return "GPS";
case CRSF_FRAMETYPE_BATTERY_SENSOR:
return "BATTERY";
case CRSF_FRAMETYPE_HEARTBEAT:
return "HEARTBEAT";
case CRSF_FRAMETYPE_VTX:
return "VTX";
case CRSF_FRAMETYPE_VTX_TELEM:
return "VTX_TELEM";
case CRSF_FRAMETYPE_PARAM_DEVICE_PING:
return "PING";
case CRSF_FRAMETYPE_COMMAND:
return "COMMAND";
case CRSF_FRAMETYPE_ATTITUDE:
return "ATTITUDE";
case CRSF_FRAMETYPE_FLIGHT_MODE:
return "FLIGHT_MODE";
case CRSF_FRAMETYPE_PARAM_DEVICE_INFO:
return "DEVICE_INFO";
case CRSF_FRAMETYPE_PARAMETER_READ:
return "PARAM_READ";
case CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY:
return "SETTINGS_ENTRY";
case CRSF_FRAMETYPE_LINK_STATISTICS:
return "LINK_STATS";
case CRSF_FRAMETYPE_RC_CHANNELS_PACKED:
return "RC";
case CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED:
return "RCv3";
case CRSF_FRAMETYPE_RC_CHANNELS_PACKED_11BIT:
return "RCv3_11BIT";
case CRSF_FRAMETYPE_LINK_STATISTICS_RX:
return "LINK_STATSv3_RX";
case CRSF_FRAMETYPE_LINK_STATISTICS_TX:
return "LINK_STATSv3_TX";
case CRSF_FRAMETYPE_PARAMETER_WRITE:
return "PARAM_WRITE";
case CRSF_FRAMETYPE_AP_CUSTOM_TELEM_LEGACY:
case CRSF_FRAMETYPE_AP_CUSTOM_TELEM:
switch (subtype) {
case CRSF_AP_CUSTOM_TELEM_SINGLE_PACKET_PASSTHROUGH:
return "AP_CUSTOM_SINGLE";
case CRSF_AP_CUSTOM_TELEM_STATUS_TEXT:
return "AP_CUSTOM_TEXT";
case CRSF_AP_CUSTOM_TELEM_MULTI_PACKET_PASSTHROUGH:
return "AP_CUSTOM_MULTI";
}
return "AP_CUSTOM";
}
return "UNKNOWN";
}
#endif // AP_CRSF_ENABLED

View File

@@ -0,0 +1,196 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Crossfire protocol definitions - shared between AP_RCProtocol_CRSF and AP_CRSF_Telem
* Crossfire constants provided by Team Black Sheep under terms of the 2-Clause BSD License
*/
#pragma once
#include "AP_CRSF_config.h"
#if AP_CRSF_ENABLED
#include <stdint.h>
#include <AP_HAL/AP_HAL_Boards.h>
#define CRSF_MAX_CHANNELS 24U // Maximum number of channels from crsf datastream
#define CRSF_FRAMELEN_MAX 64U // maximum possible framelength
#define CRSF_HEADER_LEN 2U // header length
#define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CRSF_HEADER_LEN) // maximum size of the frame length field in a packet
class AP_CRSF_Protocol {
public:
enum FrameType {
CRSF_FRAMETYPE_GPS = 0x02,
CRSF_FRAMETYPE_VARIO = 0x07,
CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
CRSF_FRAMETYPE_BARO_VARIO = 0x09,
CRSF_FRAMETYPE_HEARTBEAT = 0x0B,
CRSF_FRAMETYPE_VTX = 0x0F,
CRSF_FRAMETYPE_VTX_TELEM = 0x10,
CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED = 0x17,
CRSF_FRAMETYPE_RC_CHANNELS_PACKED_11BIT = 0x18,
CRSF_FRAMETYPE_LINK_STATISTICS_RX = 0x1C,
CRSF_FRAMETYPE_LINK_STATISTICS_TX = 0x1D,
CRSF_FRAMETYPE_ATTITUDE = 0x1E,
CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,
// Extended Header Frames, range: 0x28 to 0x96
CRSF_FRAMETYPE_PARAM_DEVICE_PING = 0x28,
CRSF_FRAMETYPE_PARAM_DEVICE_INFO = 0x29,
CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,
CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,
CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,
CRSF_FRAMETYPE_COMMAND = 0x32,
// Custom Telemetry Frames 0x7F,0x80
CRSF_FRAMETYPE_AP_CUSTOM_TELEM_LEGACY = 0x7F, // as suggested by Remo Masina for fw < 4.06
CRSF_FRAMETYPE_AP_CUSTOM_TELEM = 0x80, // reserved for ArduPilot by TBS, requires fw >= 4.06
};
// Command IDs for CRSF_FRAMETYPE_COMMAND
enum CommandID {
CRSF_COMMAND_FC = 0x01,
CRSF_COMMAND_BLUETOOTH = 0x03,
CRSF_COMMAND_OSD = 0x05,
CRSF_COMMAND_VTX = 0x08,
CRSF_COMMAND_LED = 0x09,
CRSF_COMMAND_GENERAL = 0x0A,
CRSF_COMMAND_RX = 0x10,
CRSF_COMMAND_ACK = 0xFF,
};
enum DeviceAddress {
CRSF_ADDRESS_BROADCAST = 0x00,
CRSF_ADDRESS_USB = 0x10,
CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,
CRSF_ADDRESS_RESERVED1 = 0x8A,
CRSF_ADDRESS_PNP_PRO_CURRENT_SENSOR = 0xC0,
CRSF_ADDRESS_PNP_PRO_GPS = 0xC2,
CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,
CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,
CRSF_ADDRESS_RESERVED2 = 0xCA,
CRSF_ADDRESS_RACE_TAG = 0xCC,
CRSF_ADDRESS_VTX = 0xCE,
CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,
CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,
CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE
};
// Commands for CRSF_COMMAND_GENERAL
enum CommandGeneral {
CRSF_COMMAND_GENERAL_CHILD_DEVICE_REQUEST = 0x04,
CRSF_COMMAND_GENERAL_CHILD_DEVICE_FRAME = 0x05,
CRSF_COMMAND_GENERAL_FIRMWARE_UPDATE_BOOTLOADER = 0x0A,
CRSF_COMMAND_GENERAL_FIRMWARE_UPDATE_ERASE = 0x0B,
CRSF_COMMAND_GENERAL_WRITE_SERIAL_NUMBER = 0x13,
CRSF_COMMAND_GENERAL_USER_ID = 0x15,
CRSF_COMMAND_GENERAL_SOFTWARE_PRODUCT_KEY = 0x60,
CRSF_COMMAND_GENERAL_CRSF_SPEED_PROPOSAL = 0x70, // proposed new CRSF port speed
CRSF_COMMAND_GENERAL_CRSF_SPEED_RESPONSE = 0x71, // response to the proposed CRSF port speed
};
// Commands for CRSF_COMMAND_VTX
enum CommandVTX {
CRSF_COMMAND_VTX_CHANNEL = 0x01,
CRSF_COMMAND_VTX_FREQ = 0x02,
CRSF_COMMAND_VTX_POWER = 0x03,
CRSF_COMMAND_VTX_PITMODE = 0x04,
CRSF_COMMAND_VTX_PITMODE_POWERUP = 0x05,
CRSF_COMMAND_VTX_POWER_DBM = 0x08,
};
// Commands for CRSF_COMMAND_RX
enum CommandRX {
CRSF_COMMAND_RX_BIND = 0x01,
CRSF_COMMAND_RX_CANCEL_BIND = 0x02,
CRSF_COMMAND_RX_SET_BIND_ID = 0x03,
};
// SubType IDs for CRSF_FRAMETYPE_CUSTOM_TELEM
enum CustomTelemSubTypeID : uint8_t {
CRSF_AP_CUSTOM_TELEM_SINGLE_PACKET_PASSTHROUGH = 0xF0,
CRSF_AP_CUSTOM_TELEM_STATUS_TEXT = 0xF1,
CRSF_AP_CUSTOM_TELEM_MULTI_PACKET_PASSTHROUGH = 0xF2,
};
enum class ProtocolType {
PROTOCOL_CRSF,
PROTOCOL_TRACER,
PROTOCOL_ELRS
};
struct Frame {
uint8_t device_address;
uint8_t length;
uint8_t type;
uint8_t payload[CRSF_FRAME_PAYLOAD_MAX - 1]; // type is already accounted for
} PACKED;
struct SubsetChannelsFrame {
#if __BYTE_ORDER__ != __ORDER_LITTLE_ENDIAN__
#error "Only supported on little-endian architectures"
#endif
uint8_t starting_channel:5; // which channel number is the first one in the frame
uint8_t res_configuration:2; // configuration for the RC data resolution (10 - 13 bits)
uint8_t digital_switch_flag:1; // configuration bit for digital channel
uint8_t channels[CRSF_FRAME_PAYLOAD_MAX - 2]; // payload less byte above
// uint16_t channel[]:res; // variable amount of channels (with variable resolution based
// on the res_configuration) based on the frame size
// uint16_t digital_switch_channel[]:10; // digital switch channel
} PACKED;
struct LinkStatisticsTXFrame {
uint8_t rssi_db; // RSSI(dBm*-1)
uint8_t rssi_percent; // RSSI in percent
uint8_t link_quality; // Package success rate / Link quality ( % )
int8_t snr; // SNR(dB)
uint8_t rf_power_db; // rf power in dBm
uint8_t fps; // rf frames per second (fps / 10)
} PACKED;
// CRSF_FRAMETYPE_HEARTBEAT
struct HeartbeatFrame {
uint8_t origin; // Device address
};
// CRSF_FRAMETYPE_COMMAND
struct PACKED CommandFrame {
uint8_t destination;
uint8_t origin;
uint8_t command_id;
uint8_t payload[9]; // 8 maximum for LED command + crc8
};
// CRSF_FRAMETYPE_PARAM_DEVICE_PING
struct PACKED ParameterPingFrame {
uint8_t destination;
uint8_t origin;
};
// CRSF_FRAMETYPE_PARAM_DEVICE_INFO
struct PACKED ParameterDeviceInfoFrame {
uint8_t destination;
uint8_t origin;
uint8_t payload[58]; // largest possible frame is 60
};
// get printable name for frame type (for debug)
static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0);
};
#endif // AP_CRSF_ENABLED

View File

@@ -0,0 +1,22 @@
/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <AP_RCProtocol/AP_RCProtocol_config.h>
#ifndef AP_CRSF_ENABLED
#define AP_CRSF_ENABLED AP_RCPROTOCOL_CRSF_ENABLED
#endif