Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_CRSF/AP_CRSF_Protocol.h
9670 views
1
/*
2
* This file is free software: you can redistribute it and/or modify it
3
* under the terms of the GNU General Public License as published by the
4
* Free Software Foundation, either version 3 of the License, or
5
* (at your option) any later version.
6
*
7
* This file is distributed in the hope that it will be useful, but
8
* WITHOUT ANY WARRANTY; without even the implied warranty of
9
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10
* See the GNU General Public License for more details.
11
*
12
* You should have received a copy of the GNU General Public License along
13
* with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
/*
17
* Crossfire protocol definitions - shared between AP_RCProtocol_CRSF and AP_CRSF_Telem
18
* Crossfire constants provided by Team Black Sheep under terms of the 2-Clause BSD License
19
*/
20
#pragma once
21
22
#include "AP_CRSF_config.h"
23
24
#if AP_CRSF_ENABLED
25
26
#include <stdint.h>
27
#include <AP_HAL/AP_HAL_Boards.h>
28
29
#define CRSF_MAX_CHANNELS 24U // Maximum number of channels from crsf datastream
30
#define CRSF_FRAMELEN_MAX 64U // maximum possible framelength
31
#define CRSF_HEADER_LEN 2U // header length
32
#define CRSF_FRAME_PAYLOAD_MAX (CRSF_FRAMELEN_MAX - CRSF_HEADER_LEN) // maximum size of the frame length field in a packet
33
34
class AP_CRSF_Protocol {
35
public:
36
37
enum FrameType {
38
CRSF_FRAMETYPE_GPS = 0x02,
39
CRSF_FRAMETYPE_VARIO = 0x07,
40
CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
41
CRSF_FRAMETYPE_BARO_VARIO = 0x09,
42
CRSF_FRAMETYPE_HEARTBEAT = 0x0B,
43
CRSF_FRAMETYPE_VTX = 0x0F,
44
CRSF_FRAMETYPE_VTX_TELEM = 0x10,
45
CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
46
CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
47
CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED = 0x17,
48
CRSF_FRAMETYPE_RC_CHANNELS_PACKED_11BIT = 0x18,
49
CRSF_FRAMETYPE_LINK_STATISTICS_RX = 0x1C,
50
CRSF_FRAMETYPE_LINK_STATISTICS_TX = 0x1D,
51
CRSF_FRAMETYPE_ATTITUDE = 0x1E,
52
CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,
53
// Extended Header Frames, range: 0x28 to 0x96
54
CRSF_FRAMETYPE_PARAM_DEVICE_PING = 0x28,
55
CRSF_FRAMETYPE_PARAM_DEVICE_INFO = 0x29,
56
CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,
57
CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,
58
CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,
59
CRSF_FRAMETYPE_COMMAND = 0x32,
60
// Custom Telemetry Frames 0x7F,0x80
61
CRSF_FRAMETYPE_AP_CUSTOM_TELEM_LEGACY = 0x7F, // as suggested by Remo Masina for fw < 4.06
62
CRSF_FRAMETYPE_AP_CUSTOM_TELEM = 0x80, // reserved for ArduPilot by TBS, requires fw >= 4.06
63
};
64
65
// Command IDs for CRSF_FRAMETYPE_COMMAND
66
enum CommandID {
67
CRSF_COMMAND_FC = 0x01,
68
CRSF_COMMAND_BLUETOOTH = 0x03,
69
CRSF_COMMAND_OSD = 0x05,
70
CRSF_COMMAND_VTX = 0x08,
71
CRSF_COMMAND_LED = 0x09,
72
CRSF_COMMAND_GENERAL = 0x0A,
73
CRSF_COMMAND_RX = 0x10,
74
CRSF_COMMAND_ACK = 0xFF,
75
};
76
77
enum DeviceAddress {
78
CRSF_ADDRESS_BROADCAST = 0x00,
79
CRSF_ADDRESS_USB = 0x10,
80
CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,
81
CRSF_ADDRESS_RESERVED1 = 0x8A,
82
CRSF_ADDRESS_PNP_PRO_CURRENT_SENSOR = 0xC0,
83
CRSF_ADDRESS_PNP_PRO_GPS = 0xC2,
84
CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,
85
CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,
86
CRSF_ADDRESS_RESERVED2 = 0xCA,
87
CRSF_ADDRESS_RACE_TAG = 0xCC,
88
CRSF_ADDRESS_VTX = 0xCE,
89
CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,
90
CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,
91
CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE
92
};
93
94
// Commands for CRSF_COMMAND_GENERAL
95
enum CommandGeneral {
96
CRSF_COMMAND_GENERAL_CHILD_DEVICE_REQUEST = 0x04,
97
CRSF_COMMAND_GENERAL_CHILD_DEVICE_FRAME = 0x05,
98
CRSF_COMMAND_GENERAL_FIRMWARE_UPDATE_BOOTLOADER = 0x0A,
99
CRSF_COMMAND_GENERAL_FIRMWARE_UPDATE_ERASE = 0x0B,
100
CRSF_COMMAND_GENERAL_WRITE_SERIAL_NUMBER = 0x13,
101
CRSF_COMMAND_GENERAL_USER_ID = 0x15,
102
CRSF_COMMAND_GENERAL_SOFTWARE_PRODUCT_KEY = 0x60,
103
CRSF_COMMAND_GENERAL_CRSF_SPEED_PROPOSAL = 0x70, // proposed new CRSF port speed
104
CRSF_COMMAND_GENERAL_CRSF_SPEED_RESPONSE = 0x71, // response to the proposed CRSF port speed
105
};
106
107
// Commands for CRSF_COMMAND_VTX
108
enum CommandVTX {
109
CRSF_COMMAND_VTX_CHANNEL = 0x01,
110
CRSF_COMMAND_VTX_FREQ = 0x02,
111
CRSF_COMMAND_VTX_POWER = 0x03,
112
CRSF_COMMAND_VTX_PITMODE = 0x04,
113
CRSF_COMMAND_VTX_PITMODE_POWERUP = 0x05,
114
CRSF_COMMAND_VTX_POWER_DBM = 0x08,
115
};
116
117
// Commands for CRSF_COMMAND_RX
118
enum CommandRX {
119
CRSF_COMMAND_RX_BIND = 0x01,
120
CRSF_COMMAND_RX_CANCEL_BIND = 0x02,
121
CRSF_COMMAND_RX_SET_BIND_ID = 0x03,
122
};
123
124
// SubType IDs for CRSF_FRAMETYPE_CUSTOM_TELEM
125
enum CustomTelemSubTypeID : uint8_t {
126
CRSF_AP_CUSTOM_TELEM_SINGLE_PACKET_PASSTHROUGH = 0xF0,
127
CRSF_AP_CUSTOM_TELEM_STATUS_TEXT = 0xF1,
128
CRSF_AP_CUSTOM_TELEM_MULTI_PACKET_PASSTHROUGH = 0xF2,
129
};
130
131
enum class ProtocolType {
132
PROTOCOL_CRSF,
133
PROTOCOL_TRACER,
134
PROTOCOL_ELRS
135
};
136
137
struct Frame {
138
uint8_t device_address;
139
uint8_t length;
140
uint8_t type;
141
uint8_t payload[CRSF_FRAME_PAYLOAD_MAX - 1]; // type is already accounted for
142
} PACKED;
143
144
struct SubsetChannelsFrame {
145
#if __BYTE_ORDER__ != __ORDER_LITTLE_ENDIAN__
146
#error "Only supported on little-endian architectures"
147
#endif
148
uint8_t starting_channel:5; // which channel number is the first one in the frame
149
uint8_t res_configuration:2; // configuration for the RC data resolution (10 - 13 bits)
150
uint8_t digital_switch_flag:1; // configuration bit for digital channel
151
uint8_t channels[CRSF_FRAME_PAYLOAD_MAX - 2]; // payload less byte above
152
// uint16_t channel[]:res; // variable amount of channels (with variable resolution based
153
// on the res_configuration) based on the frame size
154
// uint16_t digital_switch_channel[]:10; // digital switch channel
155
} PACKED;
156
157
struct LinkStatisticsTXFrame {
158
uint8_t rssi_db; // RSSI(dBm*-1)
159
uint8_t rssi_percent; // RSSI in percent
160
uint8_t link_quality; // Package success rate / Link quality ( % )
161
int8_t snr; // SNR(dB)
162
uint8_t rf_power_db; // rf power in dBm
163
uint8_t fps; // rf frames per second (fps / 10)
164
} PACKED;
165
166
// CRSF_FRAMETYPE_HEARTBEAT
167
struct HeartbeatFrame {
168
uint8_t origin; // Device address
169
};
170
171
// CRSF_FRAMETYPE_COMMAND
172
struct PACKED CommandFrame {
173
uint8_t destination;
174
uint8_t origin;
175
uint8_t command_id;
176
uint8_t payload[9]; // 8 maximum for LED command + crc8
177
};
178
179
// CRSF_FRAMETYPE_PARAM_DEVICE_PING
180
struct PACKED ParameterPingFrame {
181
uint8_t destination;
182
uint8_t origin;
183
};
184
185
// CRSF_FRAMETYPE_PARAM_DEVICE_INFO
186
struct PACKED ParameterDeviceInfoFrame {
187
uint8_t destination;
188
uint8_t origin;
189
uint8_t payload[58]; // largest possible frame is 60
190
};
191
192
// get printable name for frame type (for debug)
193
static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0);
194
};
195
196
#endif // AP_CRSF_ENABLED
197
198