WP altitude enforce hold fix
[inav.git] / src / main / msp / msp_protocol.h
blobb44037f2f88da17464c019196acde813cce9b88c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 /**
19 * MSP Guidelines, emphasis is used to clarify.
21 * Each FlightController (FC, Server) MUST change the API version when any MSP command is added, deleted, or changed.
23 * If you fork the FC source code and release your own version, you MUST change the Flight Controller Identifier.
25 * NEVER release a modified copy of this code that shares the same Flight controller IDENT and API version
26 * if the API doesn't match EXACTLY.
28 * Consumers of the API (API clients) SHOULD first attempt to get a response from the MSP_API_VERSION command.
30 * API consumers should ALWAYS handle communication failures gracefully and attempt to continue
31 * without the information if possible. Clients MAY log/display a suitable message.
33 * API clients should NOT attempt any communication if they can't handle the returned API MAJOR VERSION.
35 * API clients SHOULD attempt communication if the API MINOR VERSION has increased from the time
36 * the API client was written and handle command failures gracefully. Clients MAY disable
37 * functionality that depends on the commands while still leaving other functionality intact.
38 * Clients SHOULD operate in READ-ONLY mode and SHOULD present a warning to the user to state
39 * that the newer API version may cause problems before using API commands that change FC state.
41 * It is for this reason that each MSP command should be specific as possible, such that changes
42 * to commands break as little functionality as possible.
44 * API client authors MAY use a compatibility matrix/table when determining if they can support
45 * a given command from a given flight controller at a given api version level.
47 * Developers MUST NOT create new MSP commands that do more than one thing.
49 * Failure to follow these guidelines will likely invoke the wrath of developers trying to write tools
50 * that use the API and the users of those tools.
53 #pragma once
55 /* Protocol numbers used both by the wire format, config system, and
56 field setters.
59 #define MSP_PROTOCOL_VERSION 0 // Same version over MSPv1 & MSPv2 - message format didn't change and it backward compatible
61 #define API_VERSION_MAJOR 2 // increment when major changes are made
62 #define API_VERSION_MINOR 5 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
64 #define API_VERSION_LENGTH 2
66 #define MULTIWII_IDENTIFIER "MWII";
67 #define BASEFLIGHT_IDENTIFIER "BAFL";
68 #define BETAFLIGHT_IDENTIFIER "BTFL"
69 #define CLEANFLIGHT_IDENTIFIER "CLFL"
70 #define INAV_IDENTIFIER "INAV"
71 #define RACEFLIGHT_IDENTIFIER "RCFL"
73 #define FLIGHT_CONTROLLER_IDENTIFIER_LENGTH 4
74 #define FLIGHT_CONTROLLER_VERSION_LENGTH 3
75 #define FLIGHT_CONTROLLER_VERSION_MASK 0xFFF
77 #define BOARD_IDENTIFIER_LENGTH 4 // 4 UPPER CASE alpha numeric characters that identify the board being used.
78 #define BOARD_HARDWARE_REVISION_LENGTH 2
80 // These are baseflight specific flags but they are useless now since MW 2.3 uses the upper 4 bits for the navigation version.
81 #define CAP_PLATFORM_32BIT ((uint32_t)1 << 31)
82 #define CAP_BASEFLIGHT_CONFIG ((uint32_t)1 << 30)
84 // MW 2.3 stores NAVI_VERSION in the top 4 bits of the capability mask.
85 #define CAP_NAVI_VERSION_BIT_4_MSB ((uint32_t)1 << 31)
86 #define CAP_NAVI_VERSION_BIT_3 ((uint32_t)1 << 30)
87 #define CAP_NAVI_VERSION_BIT_2 ((uint32_t)1 << 29)
88 #define CAP_NAVI_VERSION_BIT_1_LSB ((uint32_t)1 << 28)
90 #define CAP_DYNBALANCE ((uint32_t)1 << 2)
91 #define CAP_FLAPS ((uint32_t)1 << 3)
92 #define CAP_NAVCAP ((uint32_t)1 << 4)
93 #define CAP_EXTAUX ((uint32_t)1 << 5)
95 #define MSP_API_VERSION 1 //out message
96 #define MSP_FC_VARIANT 2 //out message
97 #define MSP_FC_VERSION 3 //out message
98 #define MSP_BOARD_INFO 4 //out message
99 #define MSP_BUILD_INFO 5 //out message
101 #define MSP_INAV_PID 6
102 #define MSP_SET_INAV_PID 7
104 #define MSP_NAME 10 //out message Returns user set board name - betaflight
105 #define MSP_SET_NAME 11 //in message Sets board name - betaflight
107 #define MSP_NAV_POSHOLD 12
108 #define MSP_SET_NAV_POSHOLD 13
110 #define MSP_CALIBRATION_DATA 14
111 #define MSP_SET_CALIBRATION_DATA 15
113 #define MSP_POSITION_ESTIMATION_CONFIG 16
114 #define MSP_SET_POSITION_ESTIMATION_CONFIG 17
116 #define MSP_WP_MISSION_LOAD 18 // Load mission from NVRAM
117 #define MSP_WP_MISSION_SAVE 19 // Save mission to NVRAM
118 #define MSP_WP_GETINFO 20
120 #define MSP_RTH_AND_LAND_CONFIG 21
121 #define MSP_SET_RTH_AND_LAND_CONFIG 22
122 #define MSP_FW_CONFIG 23
123 #define MSP_SET_FW_CONFIG 24
125 // MSP commands for Cleanflight original features
127 #define MSP_MODE_RANGES 34 //out message Returns all mode ranges
128 #define MSP_SET_MODE_RANGE 35 //in message Sets a single mode range
130 #define MSP_FEATURE 36
131 #define MSP_SET_FEATURE 37
133 #define MSP_BOARD_ALIGNMENT 38
134 #define MSP_SET_BOARD_ALIGNMENT 39
136 #define MSP_CURRENT_METER_CONFIG 40
137 #define MSP_SET_CURRENT_METER_CONFIG 41
139 #define MSP_MIXER 42
140 #define MSP_SET_MIXER 43
142 #define MSP_RX_CONFIG 44
143 #define MSP_SET_RX_CONFIG 45
145 #define MSP_LED_COLORS 46
146 #define MSP_SET_LED_COLORS 47
148 #define MSP_LED_STRIP_CONFIG 48
149 #define MSP_SET_LED_STRIP_CONFIG 49
151 #define MSP_RSSI_CONFIG 50
152 #define MSP_SET_RSSI_CONFIG 51
154 #define MSP_ADJUSTMENT_RANGES 52
155 #define MSP_SET_ADJUSTMENT_RANGE 53
157 // private - only to be used by the configurator, the commands are likely to change
158 #define MSP_CF_SERIAL_CONFIG 54 //Deprecated and not used
159 #define MSP_SET_CF_SERIAL_CONFIG 55 //Deprecated and not used
161 #define MSP_VOLTAGE_METER_CONFIG 56
162 #define MSP_SET_VOLTAGE_METER_CONFIG 57
164 #define MSP_SONAR_ALTITUDE 58 //out message get surface altitude [cm]
166 #define MSP_ARMING_CONFIG 61 //out message Returns auto_disarm_delay and disarm_kill_switch parameters
167 #define MSP_SET_ARMING_CONFIG 62 //in message Sets auto_disarm_delay and disarm_kill_switch parameters
170 // Baseflight MSP commands (if enabled they exist in Cleanflight)
172 #define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total)
173 #define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP
175 #define MSP_REBOOT 68 //in message reboot settings
177 #define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip
178 #define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip
179 #define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip
181 #define MSP_LOOP_TIME 73 //out message Returns FC cycle time i.e looptime parameter
182 #define MSP_SET_LOOP_TIME 74 //in message Sets FC cycle time i.e looptime parameter
184 #define MSP_FAILSAFE_CONFIG 75 //out message Returns FC Fail-Safe settings
185 #define MSP_SET_FAILSAFE_CONFIG 76 //in message Sets FC Fail-Safe settings
187 #define MSP_SDCARD_SUMMARY 79 //out message Get the state of the SD card
189 #define MSP_BLACKBOX_CONFIG 80 //out message Get blackbox settings
190 #define MSP_SET_BLACKBOX_CONFIG 81 //in message Set blackbox settings
192 #define MSP_TRANSPONDER_CONFIG 82 //out message Get transponder settings
193 #define MSP_SET_TRANSPONDER_CONFIG 83 //in message Set transponder settings
195 #define MSP_OSD_CONFIG 84 //out message Get osd settings - betaflight
196 #define MSP_SET_OSD_CONFIG 85 //in message Set osd settings - betaflight
198 #define MSP_OSD_CHAR_READ 86 //out message Get osd settings - betaflight
199 #define MSP_OSD_CHAR_WRITE 87 //in message Set osd settings - betaflight
201 #define MSP_VTX_CONFIG 88 //out message Get vtx settings - betaflight
202 #define MSP_SET_VTX_CONFIG 89 //in message Set vtx settings - betaflight
204 // Betaflight Additional Commands
205 #define MSP_ADVANCED_CONFIG 90
206 #define MSP_SET_ADVANCED_CONFIG 91
208 #define MSP_FILTER_CONFIG 92
209 #define MSP_SET_FILTER_CONFIG 93
211 #define MSP_PID_ADVANCED 94
212 #define MSP_SET_PID_ADVANCED 95
214 #define MSP_SENSOR_CONFIG 96
215 #define MSP_SET_SENSOR_CONFIG 97
217 #define MSP_SPECIAL_PARAMETERS 98 // Temporary betaflight parameters before cleanup and keep CF compatibility
218 #define MSP_SET_SPECIAL_PARAMETERS 99 // Temporary betaflight parameters before cleanup and keep CF compatibility
220 #define MSP_VTXTABLE_BAND 137 //out message vtxTable band/channel data - needed by msp vtx
221 #define MSP_VTXTABLE_POWERLEVEL 138 //out message vtxTable powerLevel data - neede by msp vtx
224 // OSD specific
226 #define MSP_OSD_VIDEO_CONFIG 180
227 #define MSP_SET_OSD_VIDEO_CONFIG 181
229 #define MSP_DISPLAYPORT 182
231 #define MSP_SET_TX_INFO 186 // in message Used to send runtime information from TX lua scripts to the firmware
232 #define MSP_TX_INFO 187 // out message Used by TX lua scripts to read information from the firmware
235 // Multwii original MSP commands
238 #define MSP_STATUS 101 //out message cycletime & errors_count & sensor present & box activation & current setting number
239 #define MSP_RAW_IMU 102 //out message 9 DOF
240 #define MSP_SERVO 103 //out message servos
241 #define MSP_MOTOR 104 //out message motors
242 #define MSP_RC 105 //out message rc channels and more
243 #define MSP_RAW_GPS 106 //out message fix, numsat, lat, lon, alt, speed, ground course
244 #define MSP_COMP_GPS 107 //out message distance home, direction home
245 #define MSP_ATTITUDE 108 //out message 2 angles 1 heading
246 #define MSP_ALTITUDE 109 //out message altitude, variometer
247 #define MSP_ANALOG 110 //out message vbat, powermetersum, rssi if available on RX
248 #define MSP_RC_TUNING 111 //out message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
249 #define MSP_ACTIVEBOXES 113 //out message Active box flags (full width, more than 32 bits)
250 #define MSP_MISC 114 //out message powermeter trig
251 #define MSP_MOTOR_PINS 115 //out message which pins are in use for motors & servos, for GUI
252 #define MSP_BOXNAMES 116 //out message the aux switch names
253 #define MSP_PIDNAMES 117 //out message the PID names
254 #define MSP_WP 118 //out message get a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold
255 #define MSP_BOXIDS 119 //out message get the permanent IDs associated to BOXes
256 #define MSP_SERVO_CONFIGURATIONS 120 //out message All servo configurations.
257 #define MSP_NAV_STATUS 121 //out message Returns navigation status
258 #define MSP_NAV_CONFIG 122 //out message Returns navigation parameters
259 #define MSP_3D 124 //out message Settings needed for reversible ESCs
260 #define MSP_RC_DEADBAND 125 //out message deadbands for yaw alt pitch roll
261 #define MSP_SENSOR_ALIGNMENT 126 //out message orientation of acc,gyro,mag
262 #define MSP_LED_STRIP_MODECOLOR 127 //out message Get LED strip mode_color settings
263 #define MSP_BATTERY_STATE 130 // DJI googles fc battery info
265 #define MSP_SET_RAW_RC 200 //in message 8 rc chan
266 #define MSP_SET_RAW_GPS 201 //in message fix, numsat, lat, lon, alt, speed
267 #define MSP_SET_BOX 203 //in message BOX setup (number is dependant of your setup)
268 #define MSP_SET_RC_TUNING 204 //in message rc rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID, yaw expo
269 #define MSP_ACC_CALIBRATION 205 //in message no param
270 #define MSP_MAG_CALIBRATION 206 //in message no param
271 #define MSP_SET_MISC 207 //in message powermeter trig + 8 free for future use
272 #define MSP_RESET_CONF 208 //in message no param
273 #define MSP_SET_WP 209 //in message sets a given WP (WP#,lat, lon, alt, flags)
274 #define MSP_SELECT_SETTING 210 //in message Select Setting Number (0-2)
275 #define MSP_SET_HEAD 211 //in message define a new heading hold direction
276 #define MSP_SET_SERVO_CONFIGURATION 212 //in message Servo settings
277 #define MSP_SET_MOTOR 214 //in message PropBalance function
278 #define MSP_SET_NAV_CONFIG 215 //in message Sets nav config parameters - write to the eeprom
279 #define MSP_SET_3D 217 //in message Settings needed for reversible ESCs
280 #define MSP_SET_RC_DEADBAND 218 //in message deadbands for yaw alt pitch roll
281 #define MSP_SET_RESET_CURR_PID 219 //in message resetting the current pid profile to defaults
282 #define MSP_SET_SENSOR_ALIGNMENT 220 //in message set the orientation of the acc,gyro,mag
283 #define MSP_SET_LED_STRIP_MODECOLOR 221 //in message Set LED strip mode_color settings
285 // #define MSP_BIND 240 //in message no param
286 // #define MSP_ALARMS 242
288 #define MSP_EEPROM_WRITE 250 //in message no param
289 #define MSP_RESERVE_1 251 //reserved for system usage
290 #define MSP_RESERVE_2 252 //reserved for system usage
291 #define MSP_DEBUGMSG 253 //out message debug string buffer
292 #define MSP_DEBUG 254 //out message debug1,debug2,debug3,debug4
293 #define MSP_V2_FRAME 255 //MSPv2 payload indicator
295 // Additional commands that are not compatible with MultiWii
296 #define MSP_STATUS_EX 150 //out message cycletime, errors_count, CPU load, sensor present etc
297 #define MSP_SENSOR_STATUS 151 //out message Hardware sensor status
298 #define MSP_UID 160 //out message Unique device ID
299 #define MSP_GPSSVINFO 164 //out message get Signal Strength (only U-Blox)
300 #define MSP_GPSSTATISTICS 166 //out message get GPS debugging data
301 #define MSP_ACC_TRIM 240 //out message get acc angle trim values
302 #define MSP_SET_ACC_TRIM 239 //in message set acc angle trim values
303 #define MSP_SERVO_MIX_RULES 241 //out message Returns servo mixer configuration
304 #define MSP_SET_SERVO_MIX_RULE 242 //in message Sets servo mixer configuration
305 #define MSP_SET_PASSTHROUGH 245 //in message Sets up passthrough to different peripherals (4way interface, uart, etc...)
306 #define MSP_RTC 246 //out message Gets the RTC clock (returns: secs(i32) millis(u16) - (0,0) if time is not known)
307 #define MSP_SET_RTC 247 //in message Sets the RTC clock (args: secs(i32) millis(u16))
309 // MSPv2 includes
310 #include "msp_protocol_v2_common.h"
311 #include "msp_protocol_v2_sensor.h"
312 #include "msp_protocol_v2_inav.h"