Skip to main content

MSP Protocol Reference for Developers

This page lists all MSP (MultiWii Serial Protocol) commands defined in Betaflight firmware master, intended as a quick lookup for firmware and configurator contributors.

Direction key:

  • from FC — FC sends this message in response to a request (outbound from flight controller)
  • to FC — Configurator/GCS sends this message to the FC (inbound to flight controller)
  • both — Command works in both directions
  • system — Internal framing or reserved code
  • unknown — Direction not annotated in source; inferred from naming convention for MSP v2

Protocol versions:

  • MSP v1 codes are decimal (0–255); defined in msp_protocol.h
  • MSP v2 codes are hex (0x1000+); defined in msp_protocol_v2_common.h and msp_protocol_v2_betaflight.h
  • MSP v2 framing is indicated by MSP_V2_FRAME (255) in a v1 stream
info

This page is generated from firmware source by scripts/extract-pg-msp.js. To regenerate after a firmware update:

node scripts/extract-pg-msp.js --firmware-path <path-to-betaflight-repo>

The summary table below lists all MSP codes. The Command Parameters section further down provides per-command payload field details (byte offsets, C types, min/max values) extracted from msp.c handler implementations.

All MSP Commands

Generated from firmware commit: c925d4f68202d5882af011b3b33bb3afee9a54e3

CommandMsg IdDirectionFieldsNotes
MSP_PROTOCOL_VERSION0system
MSP_API_VERSION1from FC3Get API version
MSP_FC_VARIANT2from FC1Get flight controller variant
MSP_FC_VERSION3from FC4Get flight controller version
MSP_BOARD_INFO4from FC21Get board information
MSP_BUILD_INFO5from FC3Get build information
MSP_NAME10from FC1Returns user set board name - betaflight
MSP_SET_NAME11to FCSets board name - betaflight
MSP_BATTERY_CONFIG32from FC9Get battery configuration
MSP_SET_BATTERY_CONFIG33to FC9Set battery configuration
MSP_MODE_RANGES34from FC4Returns all mode ranges
MSP_SET_MODE_RANGE35to FC7Sets a single mode range
MSP_FEATURE_CONFIG36from FC1Get feature configuration
MSP_SET_FEATURE_CONFIG37to FC1Set feature configuration
MSP_BOARD_ALIGNMENT_CONFIG38from FC3Get board alignment configuration
MSP_SET_BOARD_ALIGNMENT_CONFIG39to FC3Set board alignment configuration
MSP_CURRENT_METER_CONFIG40from FC11Get current meter configuration
MSP_SET_CURRENT_METER_CONFIG41to FC7Set current meter configuration
MSP_MIXER_CONFIG42from FC2Get mixer configuration
MSP_SET_MIXER_CONFIG43to FC3Set mixer configuration
MSP_RX_CONFIG44from FC38Get RX configuration
MSP_SET_RX_CONFIG45to FC36Set RX configuration
MSP_LED_COLORS46from FC3Get LED colors
MSP_SET_LED_COLORS47to FC3Set LED colors
MSP_LED_STRIP_CONFIG48from FC5Get LED strip configuration
MSP_SET_LED_STRIP_CONFIG49to FC4Set LED strip configuration
MSP_RSSI_CONFIG50from FC1Get RSSI configuration
MSP_SET_RSSI_CONFIG51to FC1Set RSSI configuration
MSP_ADJUSTMENT_RANGES52from FC8Get adjustment ranges
MSP_SET_ADJUSTMENT_RANGE53to FC9Set adjustment range
MSP_CF_SERIAL_CONFIG54from FC6Get Cleanflight serial configuration
MSP_SET_CF_SERIAL_CONFIG55to FC6Set Cleanflight serial configuration
MSP_VOLTAGE_METER_CONFIG56from FC7Get voltage meter configuration
MSP_SET_VOLTAGE_METER_CONFIG57to FC7Set voltage meter configuration
MSP_SONAR_ALTITUDE58from FC2Get sonar altitude [cm]
MSP_PID_CONTROLLER59from FC1Get PID controller
MSP_SET_PID_CONTROLLER60to FCSet PID controller
MSP_ARMING_CONFIG61from FC4Get arming configuration
MSP_SET_ARMING_CONFIG62to FC4Set arming configuration
MSP_RX_MAP64from FC1Get RX map (also returns number of channels total)
MSP_SET_RX_MAP65to FC1Set RX map, numchannels to set comes from MSP_RX_MAP
MSP_REBOOT68to FC3Reboot settings
MSP_DATAFLASH_SUMMARY70from FCGet description of dataflash chip
MSP_DATAFLASH_READ71from FCGet content of dataflash chip
MSP_DATAFLASH_ERASE72to FCErase dataflash chip
MSP_FAILSAFE_CONFIG75from FC6Get failsafe settings
MSP_SET_FAILSAFE_CONFIG76to FC6Set failsafe settings
MSP_RXFAIL_CONFIG77from FC2Get RX failsafe settings
MSP_SET_RXFAIL_CONFIG78to FC3Set RX failsafe settings
MSP_SDCARD_SUMMARY79from FCGet SD card state
MSP_BLACKBOX_CONFIG80from FC14Get blackbox settings
MSP_SET_BLACKBOX_CONFIG81to FC6Set blackbox settings
MSP_TRANSPONDER_CONFIG82from FC6Get transponder settings
MSP_SET_TRANSPONDER_CONFIG83to FC2Set transponder settings
MSP_OSD_CONFIG84from FC27Get OSD settings
MSP_SET_OSD_CONFIG85to FC21Set OSD settings
MSP_OSD_CHAR_READ86from FCGet OSD characters
MSP_OSD_CHAR_WRITE87to FC5Set OSD characters
MSP_VTX_CONFIG88from FC17Get VTX settings
MSP_SET_VTX_CONFIG89to FC16Set VTX settings
MSP_ADVANCED_CONFIG90from FC16Get advanced configuration
MSP_SET_ADVANCED_CONFIG91to FC15Set advanced configuration
MSP_FILTER_CONFIG92from FC50Get filter configuration
MSP_SET_FILTER_CONFIG93to FC50Set filter configuration
MSP_PID_ADVANCED94from FC70Get advanced PID settings
MSP_SET_PID_ADVANCED95to FC70Set advanced PID settings
MSP_SENSOR_CONFIG96from FC10Get sensor configuration
MSP_SET_SENSOR_CONFIG97to FC10Set sensor configuration
MSP_CAMERA_CONTROL98both1Camera control
MSP_SET_ARMING_DISABLED99to FC2Enable/disable arming
MSP_STATUS101from FC20Cycletime & errors_count & sensor present & box activation & current setting number
MSP_RAW_IMU102from FC59 DOF
MSP_SERVO103from FC1Servos
MSP_MOTOR104from FC3Motors
MSP_RC105from FC1RC channels and more
MSP_RAW_GPS106from FC8Fix, numsat, lat, lon, alt, speed, ground course
MSP_COMP_GPS107from FC3Distance home, direction home
MSP_ATTITUDE108from FC32 angles 1 heading
MSP_ALTITUDE109from FC3Altitude, variometer
MSP_ANALOG110from FC5Vbat, powermetersum, rssi if available on RX
MSP_RC_TUNING111from FC18RC rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID
MSP_PID112from FC3P I D coeff (9 are used currently)
MSP_BOXNAMES116from FCThe aux switch names
MSP_PIDNAMES117from FC1The PID names
MSP_WP118from FCGet a WP, WP# is in the payload, returns (WP#, lat, lon, alt, flags) WP#0-home, WP#16-poshold
MSP_BOXIDS119from FCGet the permanent IDs associated to BOXes
MSP_SERVO_CONFIGURATIONS120from FC6All servo configurations
MSP_NAV_STATUS121from FCReturns navigation status
MSP_NAV_CONFIG122from FCReturns navigation parameters
MSP_MOTOR_3D_CONFIG124from FC3Settings needed for reversible ESCs
MSP_RC_DEADBAND125from FC5Deadbands for yaw alt pitch roll
MSP_SENSOR_ALIGNMENT126from FC12Orientation of acc,gyro,mag
MSP_LED_STRIP_MODECOLOR127from FC9Get LED strip mode_color settings
MSP_VOLTAGE_METERS128from FC2Voltage (per meter)
MSP_CURRENT_METERS129from FC3Amperage (per meter)
MSP_BATTERY_STATE130from FC7Connected/Disconnected, Voltage, Current Used
MSP_MOTOR_CONFIG131from FC9Motor configuration (min/max throttle, etc)
MSP_GPS_CONFIG132from FC6GPS configuration
MSP_COMPASS_CONFIG133from FC1Compass configuration
MSP_ESC_SENSOR_DATA134from FC6Extra ESC data from 32-Bit ESCs (Temperature, RPM)
MSP_GPS_RESCUE135from FC15GPS Rescue angle, returnAltitude, descentDistance, groundSpeed, sanityChecks and minSats
MSP_GPS_RESCUE_PIDS136from FC7GPS Rescue throttleP and velocity PIDS + yaw P
MSP_VTXTABLE_BAND137from FC7VTX table band/channel data
MSP_VTXTABLE_POWERLEVEL138from FC4VTX table powerLevel data
MSP_MOTOR_TELEMETRY139from FC7Per-motor telemetry data (RPM, packet stats, ESC temp, etc.)
MSP_SIMPLIFIED_TUNING140from FCGet simplified tuning values and enabled state
MSP_SET_SIMPLIFIED_TUNING141to FCSet simplified tuning positions and apply calculated tuning
MSP_CALCULATE_SIMPLIFIED_PID142from FCCalculate PID values based on sliders without saving
MSP_CALCULATE_SIMPLIFIED_GYRO143from FCCalculate gyro filter values based on sliders without saving
MSP_CALCULATE_SIMPLIFIED_DTERM144from FCCalculate D term filter values based on sliders without saving
MSP_VALIDATE_SIMPLIFIED_TUNING145from FC3Returns array of true/false showing which simplified tuning groups match values
MSP_STATUS_EX150from FCCycletime, errors_count, CPU load, sensor present etc
MSP_UID160from FC3Unique device ID
MSP_GPSSVINFO164from FC5Get Signal Strength (only U-Blox)
MSP_GPSSTATISTICS166from FCGet GPS debugging data
MSP_ATTITUDE_QUATERNION167from FC4Orientation quaternion components (w, x, y, z)
MSP_OSD_VIDEO_CONFIG180from FCGet OSD video settings
MSP_SET_OSD_VIDEO_CONFIG181to FCSet OSD video settings
MSP_DISPLAYPORT182from FCExternal OSD displayport mode
MSP_COPY_PROFILE183to FC3Copy settings between profiles
MSP_BEEPER_CONFIG184from FC3Get beeper configuration
MSP_SET_BEEPER_CONFIG185to FC3Set beeper configuration
MSP_SET_TX_INFO186to FC1Set runtime information from TX lua scripts
MSP_TX_INFO187from FC2Get runtime information for TX lua scripts
MSP_SET_OSD_CANVAS188to FC2Set OSD canvas size COLSxROWS
MSP_OSD_CANVAS189from FC2Get OSD canvas size COLSxROWS
MSP_SET_RAW_RC200to FC18 rc chan
MSP_SET_RAW_GPS201to FC6Fix, numsat, lat, lon, alt, speed
MSP_SET_PID202to FC3P I D coeff (9 are used currently)
MSP_SET_RC_TUNING204to FC18RC rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID, yaw expo
MSP_ACC_CALIBRATION205to FCNo param - calibrate accelerometer
MSP_MAG_CALIBRATION206to FCNo param - calibrate magnetometer
MSP_RESET_CONF208to FC1No param - reset settings
MSP_SET_WP209to FCSets a given WP (WP#,lat, lon, alt, flags)
MSP_SELECT_SETTING210to FC1Select setting number (0-2)
MSP_SET_HEADING211to FC1Define a new heading hold direction
MSP_SET_SERVO_CONFIGURATION212to FC7Servo settings
MSP_SET_MOTOR214to FC1PropBalance function
MSP_SET_NAV_CONFIG215to FCSets nav config parameters
MSP_SET_MOTOR_3D_CONFIG217to FC3Settings needed for reversible ESCs
MSP_SET_RC_DEADBAND218to FC5Deadbands for yaw alt pitch roll
MSP_SET_RESET_CURR_PID219to FCReset current PID profile to defaults
MSP_SET_SENSOR_ALIGNMENT220to FC11Set the orientation of acc,gyro,mag
MSP_SET_LED_STRIP_MODECOLOR221to FC3Set LED strip mode_color settings
MSP_SET_MOTOR_CONFIG222to FC6Motor configuration (min/max throttle, etc)
MSP_SET_GPS_CONFIG223to FC6GPS configuration
MSP_SET_COMPASS_CONFIG224to FC1Compass configuration
MSP_SET_GPS_RESCUE225to FC15Set GPS Rescue parameters
MSP_SET_GPS_RESCUE_PIDS226to FC7Set GPS Rescue PID values
MSP_SET_VTXTABLE_BAND227to FC7Set vtxTable band/channel data
MSP_SET_VTXTABLE_POWERLEVEL228to FC4Set vtxTable powerLevel data
MSP_MULTIPLE_MSP230from FCRequest multiple MSPs in one request
MSP_MODE_RANGES_EXTRA238from FC4Extra mode range data
MSP_SET_ACC_TRIM239to FC2Set acc angle trim values
MSP_ACC_TRIM240from FC2Get acc angle trim values
MSP_SERVO_MIX_RULES241from FC7Get servo mixer configuration
MSP_SET_SERVO_MIX_RULE242to FC8Set servo mixer configuration
MSP_SET_PASSTHROUGH245to FCSet passthrough to peripherals
MSP_SET_RTC246to FC2Set the RTC clock
MSP_RTC247from FC7Get the RTC clock
MSP_SET_BOARD_INFO248to FC2Set the board information
MSP_SET_SIGNATURE249to FCSet the signature of the board and serial number
MSP_EEPROM_WRITE250to FCWrite settings to EEPROM
MSP_RESERVE_1251systemreserved for system usage
MSP_RESERVE_2252systemreserved for system usage
MSP_DEBUGMSG253from FCdebug string buffer
MSP_DEBUG254from FC1debug1,debug2,debug3,debug4
MSP_V2_FRAME255systemMSPv2 payload indicator
MSP2_COMMON_SERIAL_CONFIG0x1009from FC7
MSP2_COMMON_SET_SERIAL_CONFIG0x100ato FC8
MSP2_SENSOR_GPS0x1f03to FC23
MSP2_SENSOR_RANGEFINDER_LIDARMT0x1f01to FC
MSP2_SENSOR_OPTICALFLOW_MT0x1f02to FC
MSP2_BETAFLIGHT_BIND0x3000to FC
MSP2_MOTOR_OUTPUT_REORDERING0x3001from FC2
MSP2_SET_MOTOR_OUTPUT_REORDERING0x3002to FC2
MSP2_SEND_DSHOT_COMMAND0x3003to FC4
MSP2_GET_VTX_DEVICE_STATUS0x3004from FC
MSP2_GET_OSD_WARNINGS0x3005from FC2returns active OSD warning message text
MSP2_GET_TEXT0x3006from FC2
MSP2_SET_TEXT0x3007to FC2
MSP2_GET_LED_STRIP_CONFIG_VALUES0x3008from FC3
MSP2_SET_LED_STRIP_CONFIG_VALUES0x3009to FC3
MSP2_SENSOR_CONFIG_ACTIVE0x300afrom FC12
MSP2_SENSOR_OPTICALFLOW0x300bunknown
MSP2_MCU_INFO0x300cfrom FC2
MSP2_GYRO_SENSOR_ACTIVE0x300dfrom FC2
MSP2_BATTERY_PROFILE0x300efrom FC8
MSP2_SET_BATTERY_PROFILE0x300fto FC8
MSP2_CLI_SETTING0x3010from FC1
MSP2_CLI_SETTING_INFO0x3011from FC1

Command Parameters

Per-command payload field tables: byte offset, field name, C type, size, and min/max where known. Fields are extracted from msp.c handler implementations; only commands with parseable handlers appear here.

MSP_API_VERSION — 1 — from FC

Get API version

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81

MSP_FC_VARIANT — 2 — from FC

Get flight controller variant

OffsetFieldTypeBytesDefaultMinMaxNotes
0(variable data)bytes?variable-length data

MSP_FC_VERSION — 3 — from FC

Get flight controller version

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81year since 2000
1(value)U81
2(value)U81
3(string)str?string data

MSP_BOARD_INFO — 4 — from FC

Get board information

OffsetFieldTypeBytesDefaultMinMaxNotes
0(variable data)bytes?variable-length data
?(value)U162
?(value)U162No other build targets currently have hardware revision detection.
?(value)U812 == FC with MAX7456
?(value)U810 == FC
?(value)U81
?(string)str?string data
?(string)str?string data
?(string)str?string data
?(value)U81deprecated/padding
?(value)U81deprecated/padding
?(variable data)bytes?variable-length data
?(variable data)bytes?variable-length data
?(value)U81
?configurationStateU81CONFIGURATION_STATE_UNCONFIGURED
?sampleRateHzU162informational so the configurator can display the correct gyro/pid frequencies in the drop-down
?(value)U324
?(value)U81
?(value)U81deprecated/padding
?(value)U81
?(value)U81deprecated/padding

MSP_BUILD_INFO — 5 — from FC

Get build information

OffsetFieldTypeBytesDefaultMinMaxNotes
0(variable data)bytes?variable-length data
?(variable data)bytes?variable-length data
?(variable data)bytes?variable-length data

MSP_NAME — 10 — from FC

Returns user set board name - betaflight

OffsetFieldTypeBytesDefaultMinMaxNotes
0(string)str?string data

MSP_BATTERY_CONFIG — 32 — from FC

Get battery configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81
3batteryCapacityU162020000
5voltageMeterSourceU81DEFAULT_VOLTAGE_METER_SOURCElookup: TABLE_VOLTAGE_METER
6currentMeterSourceU81DEFAULT_CURRENT_METER_SOURCElookup: TABLE_CURRENT_METER
7vbatmincellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX
9vbatmaxcellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX
11vbatwarningcellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX

MSP_SET_BATTERY_CONFIG — 33 — to FC

Set battery configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81vbatlevel_warn1 in MWC2.3 GUI
1(read)U81vbatlevel_warn2 in MWC2.3 GUI
2(read)U81vbatlevel when buzzer starts to alert
3(read)U162
5voltageMeterSourceU81DEFAULT_VOLTAGE_METER_SOURCElookup: TABLE_VOLTAGE_METER
6currentMeterSourceU81DEFAULT_CURRENT_METER_SOURCElookup: TABLE_CURRENT_METER
7(read)U162
9(read)U162
11(read)U162

MSP_MODE_RANGES — 34 — from FC

Returns all mode ranges

OffsetFieldTypeBytesDefaultMinMaxNotes
0permanentIdU81
1auxChannelIndexU81
2startStepU81
3endStepU81

MSP_SET_MODE_RANGE — 35 — to FC

Sets a single mode range

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2auxChannelIndexU81
3(read)U81deprecated/ignored
4(read)U81deprecated/ignored
5modeLogicU81
6(read)U81deprecated/ignored

MSP_FEATURE_CONFIG — 36 — from FC

Get feature configuration

| Offset | Field | Type | Bytes | Default | Min | Max | Notes | | ------ | --------------- | ---- | ----- | ---------------- | ------------------ | -------------------- | --------------- | --- | --- | --- | | 0 | enabledFeatures | U32 | 4 | DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_ANTI_GRAVITY | FEATURE_AIRMODE | | | |

MSP_SET_FEATURE_CONFIG — 37 — to FC

Set feature configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U324

MSP_BOARD_ALIGNMENT_CONFIG — 38 — from FC

Get board alignment configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0rollDegreesU162DEFAULT_ALIGN_BOARD_ROLL-180360
2pitchDegreesU162DEFAULT_ALIGN_BOARD_PITCH-180360
4yawDegreesU162DEFAULT_ALIGN_BOARD_YAW-180360

MSP_SET_BOARD_ALIGNMENT_CONFIG — 39 — to FC

Set board alignment configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0rollDegreesU162DEFAULT_ALIGN_BOARD_ROLL-180360
2pitchDegreesU162DEFAULT_ALIGN_BOARD_PITCH-180360
4yawDegreesU162DEFAULT_ALIGN_BOARD_YAW-180360

MSP_CURRENT_METER_CONFIG — 40 — from FC

Get current meter configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81the id of the meter
3(value)U81indicate the type of sensor that the next part of the payload is for
4scaleU162DEFAULT_CURRENT_METER_SCALE-1600016000
6offsetU162DEFAULT_CURRENT_METER_OFFSET-3200032000
8(value)U81
9(value)U81the id of the meter
10(value)U81indicate the type of sensor that the next part of the payload is for
11scaleU162DEFAULT_CURRENT_METER_SCALE-1600016000
13offsetU162DEFAULT_CURRENT_METER_OFFSET-3200032000

MSP_SET_CURRENT_METER_CONFIG — 41 — to FC

Set current meter configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1scaleU162DEFAULT_CURRENT_METER_SCALE-1600016000
3offsetU162DEFAULT_CURRENT_METER_OFFSET-3200032000
5scaleU162DEFAULT_CURRENT_METER_SCALE-1600016000
7offsetU162DEFAULT_CURRENT_METER_OFFSET-3200032000
9(read)U162
11(read)U162

MSP_MIXER_CONFIG — 42 — from FC

Get mixer configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0mixerModeU81DEFAULT_MIXER
1yaw_motors_reversedU81YAW_MOTORS_REVERSEDlookup: TABLE_OFF_ON

MSP_SET_MIXER_CONFIG — 43 — to FC

Set mixer configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0mixerModeU81DEFAULT_MIXER
1(read)U81deprecated/ignored
2yaw_motors_reversedU81YAW_MOTORS_REVERSEDlookup: TABLE_OFF_ON

MSP_RX_CONFIG — 44 — from FC

Get RX configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0serialrx_providerU81lookup: TABLE_SERIAL_RX
1maxcheckU162PWM_PULSE_MINPWM_PULSE_MAX
3midrcU16212001700
5mincheckU162PWM_PULSE_MINPWM_PULSE_MAX
7spektrum_sat_bindU81SPEKTRUM_SAT_BIND_DISABLEDSPEKTRUM_SAT_BIND_MAX
8rx_min_usecU162PWM_PULSE_MINPWM_PULSE_MAX
10rx_max_usecU162PWM_PULSE_MINPWM_PULSE_MAX
12(value)U81not required in API 1.44, was rxConfig()->rcInterpolation
13(value)U81not required in API 1.44, was rxConfig()->rcInterpolationInterval
14(value)U162
16rx_spi_protocolU810lookup: TABLE_RX_SPI
17rx_spi_idU324
21rx_spi_rf_channel_countU81
22(value)U81deprecated/padding
23(value)U324deprecated/padding
27(value)U81deprecated/padding
28fpvCamAngleDegreesU81090
29(value)U81not required in API 1.44, was rxConfig()->rcSmoothingChannels
30(value)U81not required in API 1.44, was rxConfig()->rc_smoothing_type
31rc_smoothing_setpoint_cutoffU810UINT8_MAX
32rc_smoothing_throttle_cutoffU810UINT8_MAXwas rc_smoothing_feedforward_cutoff
33rc_smoothing_auto_factor_throttleU81RC_SMOOTHING_AUTO_FACTOR_MINRC_SMOOTHING_AUTO_FACTOR_MAX, was rxConfig()->rc_smoothing_input_type
34(value)U81not required in API 1.44, was rxConfig()->rc_smoothing_derivative_type
35(value)U81deprecated/padding
36(value)U81deprecated/padding
37(value)U81deprecated/padding
38(value)U81deprecated/padding
39(value)U81deprecated/padding
40typeU81DEFAULTlookup: TABLE_OFF_ON
41(value)U81deprecated/padding
42rc_smoothing_auto_factor_rpyU81RC_SMOOTHING_AUTO_FACTOR_MINRC_SMOOTHING_AUTO_FACTOR_MAX
43(value)U81deprecated/padding
44rc_smoothingU81lookup: TABLE_OFF_ON
45(value)U81deprecated/padding
46(variable data)bytes?variable-length data
?(variable data)bytes?variable-length data
?modelIdU810xFF0UINT8_MAX
?(value)U81deprecated/padding

MSP_SET_RX_CONFIG — 45 — to FC

Set RX configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0serialrx_providerU81lookup: TABLE_SERIAL_RX
1maxcheckU162PWM_PULSE_MINPWM_PULSE_MAX
3midrcU16212001700
5mincheckU162PWM_PULSE_MINPWM_PULSE_MAX
7spektrum_sat_bindU81SPEKTRUM_SAT_BIND_DISABLEDSPEKTRUM_SAT_BIND_MAX
8rx_min_usecU162PWM_PULSE_MINPWM_PULSE_MAX
10rx_max_usecU162PWM_PULSE_MINPWM_PULSE_MAX
12(read)U81not required in API 1.44, was rxConfigMutable()->rcInterpolation
13(read)U81not required in API 1.44, was rxConfigMutable()->rcInterpolationInterval
14(read)U162
16rx_spi_protocolU810lookup: TABLE_RX_SPI
17rx_spi_idU324
21rx_spi_rf_channel_countU81
22(read)U81deprecated/ignored
23(read)U324
27(read)U81deprecated/ignored
28fpvCamAngleDegreesU81090
29(read)U81not required in API 1.44, was rxConfigMutable()->rcSmoothingChannels
30(read)U81not required in API 1.44, was rc_smoothing_type
31(read)U81deprecated/ignored
32(read)U81was rc_smoothing_feedforward_cutoff
33(read)U81was rc_smoothing_input_type
34(read)U81not required in API 1.44, was rc_smoothing_derivative_type
35(read)U81deprecated/ignored
36(read)U81deprecated/ignored
37(read)U81deprecated/ignored
38(read)U81deprecated/ignored
39(read)U81deprecated/ignored
40typeU81DEFAULTlookup: TABLE_OFF_ON
41(read)U81deprecated/ignored
42(read)U81deprecated/ignored
43(read)U81deprecated/ignored
44(read)U81deprecated/ignored
45(read)U81deprecated/ignored
46modelIdU810xFF0UINT8_MAX
47(read)U81deprecated/ignored

MSP_LED_COLORS — 46 — from FC

Get LED colors

OffsetFieldTypeBytesDefaultMinMaxNotes
0hU162
2sU81
3vU81

MSP_SET_LED_COLORS — 47 — to FC

Set LED colors

OffsetFieldTypeBytesDefaultMinMaxNotes
0hU162
2sU81
3vU81

MSP_LED_STRIP_CONFIG — 48 — from FC

Get LED strip configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U324
4(value)U324deprecated/padding
8(value)U81advanced ledstrip available
9(value)U81only simple ledstrip available
10ledstrip_profileU81LED_PROFILE_STATUSlookup: TABLE_LED_PROFILE

MSP_SET_LED_STRIP_CONFIG — 49 — to FC

Set LED strip configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U324
5(read)U324
9ledstrip_profileU81LED_PROFILE_STATUSlookup: TABLE_LED_PROFILE

MSP_RSSI_CONFIG — 50 — from FC

Get RSSI configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0rssi_channelU810MAX_SUPPORTED_RC_CHANNEL_COUNT

MSP_SET_RSSI_CONFIG — 51 — to FC

Set RSSI configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0rssi_channelU810MAX_SUPPORTED_RC_CHANNEL_COUNT

MSP_ADJUSTMENT_RANGES — 52 — from FC

Get adjustment ranges

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81was adjRange->adjustmentIndex
1auxChannelIndexU81
2startStepU81
3endStepU81
4adjustmentConfigU81
5auxSwitchChannelIndexU81
6adjustmentCenterU162
8adjustmentScaleU162

MSP_SET_ADJUSTMENT_RANGE — 53 — to FC

Set adjustment range

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81was adjRange->adjustmentIndex
2auxChannelIndexU81
3(read)U81deprecated/ignored
4(read)U81deprecated/ignored
5adjustmentConfigU81
6auxSwitchChannelIndexU81
7adjustmentCenterU162
9adjustmentScaleU162

MSP_CF_SERIAL_CONFIG — 54 — from FC

Get Cleanflight serial configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0identifierU81
1functionMaskU162
3msp_baudrateIndexU81
4gps_baudrateIndexU81
5telemetry_baudrateIndexU81
6blackbox_baudrateIndexU81

MSP_SET_CF_SERIAL_CONFIG — 55 — to FC

Set Cleanflight serial configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1functionMaskU162
3msp_baudrateIndexU81
4gps_baudrateIndexU81
5telemetry_baudrateIndexU81
6blackbox_baudrateIndexU81

MSP_VOLTAGE_METER_CONFIG — 56 — from FC

Get voltage meter configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81voltage meters in payload
1(value)U81ADC sensor sub-frame length
2(value)U81id of the sensor
3(value)U81indicate the type of sensor that the next part of the payload is for
4vbatscaleU81VBAT_SCALE_MINVBAT_SCALE_MAX
5vbatresdivvalU81VBAT_DIVIDER_MINVBAT_DIVIDER_MAX
6vbatresdivmultiplierU81VBAT_MULTIPLIER_MINVBAT_MULTIPLIER_MAX

MSP_SET_VOLTAGE_METER_CONFIG — 57 — to FC

Set voltage meter configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored
3(read)U81deprecated/ignored
4(read)U81deprecated/ignored
5(read)U81deprecated/ignored
6(read)U81deprecated/ignored

MSP_SONAR_ALTITUDE — 58 — from FC

Get sonar altitude [cm]

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U324
4(value)U324deprecated/padding

MSP_PID_CONTROLLER — 59 — from FC

Get PID controller

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81

MSP_ARMING_CONFIG — 61 — from FC

Get arming configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0auto_disarm_delayU815060
1(value)U81deprecated/padding
2small_angleU81DEFAULT_SMALL_ANGLE0180
3gyro_cal_on_first_armU810lookup: TABLE_OFF_ON

MSP_SET_ARMING_CONFIG — 62 — to FC

Set arming configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0auto_disarm_delayU815060
1(read)U81reserved. disarm_kill_switch was removed in #5073
2small_angleU81DEFAULT_SMALL_ANGLE0180
3gyro_cal_on_first_armU810lookup: TABLE_OFF_ON

MSP_RX_MAP — 64 — from FC

Get RX map (also returns number of channels total)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(variable data)bytes?variable-length data

MSP_SET_RX_MAP — 65 — to FC

Set RX map, numchannels to set comes from MSP_RX_MAP

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored

MSP_REBOOT — 68 — to FC

Reboot settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81deprecated/padding

MSP_FAILSAFE_CONFIG — 75 — from FC

Get failsafe settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0failsafe_delayU8115
1failsafe_landing_timeU81600250
2failsafe_throttleU1621000PWM_PULSE_MINPWM_PULSE_MAX
4failsafe_switch_modeU81FAILSAFE_SWITCH_MODE_STAGE1lookup: TABLE_FAILSAFE_SWITCH_MODE
5failsafe_throttle_low_delayU1621000300
7failsafe_procedureU81FAILSAFE_PROCEDURE_DROP_ITlookup: TABLE_FAILSAFE

MSP_SET_FAILSAFE_CONFIG — 76 — to FC

Set failsafe settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0failsafe_delayU8115
1failsafe_landing_timeU81600250
2failsafe_throttleU1621000PWM_PULSE_MINPWM_PULSE_MAX
4failsafe_switch_modeU81FAILSAFE_SWITCH_MODE_STAGE1lookup: TABLE_FAILSAFE_SWITCH_MODE
5failsafe_throttle_low_delayU1621000300
7failsafe_procedureU81FAILSAFE_PROCEDURE_DROP_ITlookup: TABLE_FAILSAFE

MSP_RXFAIL_CONFIG — 77 — from FC

Get RX failsafe settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0modeU81BLACKBOX_MODE_NORMALlookup: TABLE_BLACKBOX_MODE
1(value)U162

MSP_SET_RXFAIL_CONFIG — 78 — to FC

Set RX failsafe settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U162

MSP_BLACKBOX_CONFIG — 80 — from FC

Get blackbox settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81Blackbox supported
1deviceU81DEFAULT_BLACKBOX_DEVICE0ADCDEV_COUNT
2(value)U81Rate numerator, not used anymore
3(value)U81
4(value)U162
6sample_rateU81BLACKBOX_RATE_QUARTERlookup: TABLE_BLACKBOX_SAMPLE_RATE
7fields_disabled_maskU3240
11(value)U81Blackbox not supported
12(value)U81deprecated/padding
13(value)U81deprecated/padding
14(value)U81deprecated/padding
15(value)U162deprecated/padding
17(value)U81deprecated/padding
18(value)U324deprecated/padding

MSP_SET_BLACKBOX_CONFIG — 81 — to FC

Set blackbox settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0deviceU81DEFAULT_BLACKBOX_DEVICE0ADCDEV_COUNT
1(read)U81was rate_num
2(read)U81was rate_denom
3(read)U162
5sample_rateU81BLACKBOX_RATE_QUARTERlookup: TABLE_BLACKBOX_SAMPLE_RATE
6fields_disabled_maskU3240

MSP_TRANSPONDER_CONFIG — 82 — from FC

Get transponder settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1providerU81GPS_VIRTUALlookup: TABLE_GPS_PROVIDER
2dataLengthU81
3(value)U81
4(value)U81
5(value)U81no providers

MSP_SET_TRANSPONDER_CONFIG — 83 — to FC

Set transponder settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored

MSP_OSD_CONFIG — 84 — from FC

Get OSD settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1video_systemU81VIDEO_SYSTEM_HDlookup: TABLE_VIDEO_SYSTEM
2(value)U81
3unitsU81UNIT_METRIClookup: TABLE_UNIT
4rssi_alarmU81200100
5cap_alarmU1622200020000
7(value)U81deprecated/padding
8(value)U81
9alt_alarmU162100010000
11(value)U162
13(value)U81
14(value)U81
15(value)U81
16(value)U162
18(value)U162
20(value)U81
21enabledWarningsU324
25(value)U81available profiles
26osdProfileIndexU8111OSD_PROFILE_COUNTselected profile
27(value)U81
28(value)U81
29overlay_radio_modeU81214
30(value)U81deprecated/padding
31camera_frame_widthU8124OSD_CAMERA_FRAME_MIN_WIDTHOSD_CAMERA_FRAME_MAX_WIDTH
32camera_frame_heightU8111OSD_CAMERA_FRAME_MIN_HEIGHTOSD_CAMERA_FRAME_MAX_HEIGHT
33link_quality_alarmU162800100
35rssi_dbm_alarmU162-60CRSF_RSSI_MINCRSF_RSSI_MAX

MSP_SET_OSD_CONFIG — 85 — to FC

Set OSD settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2unitsU81UNIT_METRIClookup: TABLE_UNIT
3rssi_alarmU81200100
4cap_alarmU1622200020000
6(read)U162Skip unused (previously fly timer)
8alt_alarmU162100010000
10enabledWarningsU162
12enabledWarningsU324
16(read)U81deprecated/ignored
17(read)U81deprecated/ignored
18overlay_radio_modeU81214
19(read)U81deprecated/ignored
20camera_frame_widthU8124OSD_CAMERA_FRAME_MIN_WIDTHOSD_CAMERA_FRAME_MAX_WIDTH
21camera_frame_heightU8111OSD_CAMERA_FRAME_MIN_HEIGHTOSD_CAMERA_FRAME_MAX_HEIGHT
22link_quality_alarmU162800100
24rssi_dbm_alarmU162-60CRSF_RSSI_MINCRSF_RSSI_MAX
26(read)U81deprecated/ignored
27(read)U162
29(read)U162
31(read)U81deprecated/ignored

MSP_OSD_CHAR_WRITE — 87 — to FC

Set OSD characters

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162
2(read)U81deprecated/ignored
3(read)U162
5(read)U81deprecated/ignored
6(read)U81deprecated/ignored

MSP_VTX_CONFIG — 88 — from FC

Get VTX settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1bandU8100VTX_TABLE_MAX_BANDS
2channelU8100VTX_TABLE_MAX_CHANNELS
3powerU810
4(value)U81
5freqU16200VTX_SETTINGS_MAX_FREQUENCY_MHZ
7(value)U81
8lowPowerDisarmU81VTX_LOW_POWER_DISARM_OFFlookup: TABLE_VTX_LOW_POWER_DISARM
9pitModeFreqU16200VTX_SETTINGS_MAX_FREQUENCY_MHZ
11(value)U81vtxtable is available
12bandsU810
13channelsU810
14powerLevelsU810
15(value)U81deprecated/padding
16(value)U81deprecated/padding
17(value)U81deprecated/padding
18(value)U81deprecated/padding

MSP_SET_VTX_CONFIG — 89 — to FC

Set VTX settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162
2powerU810
3(read)U81deprecated/ignored
4lowPowerDisarmU81VTX_LOW_POWER_DISARM_OFFlookup: TABLE_VTX_LOW_POWER_DISARM
5pitModeFreqU16200VTX_SETTINGS_MAX_FREQUENCY_MHZ
7(read)U81deprecated/ignored
8(read)U81deprecated/ignored
9(read)U162
11(read)U81deprecated/ignored
12(read)U81deprecated/ignored
13(read)U81deprecated/ignored
14(read)U81deprecated/ignored
15(read)U81deprecated/ignored
16(read)U81deprecated/ignored
17(read)U81deprecated/ignored
18(read)U81deprecated/ignored

MSP_ADVANCED_CONFIG — 90 — from FC

Get advanced configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81was gyroConfig()->gyro_sync_denom - removed in API 1.43
1pid_process_denomU81DEFAULT_PID_PROCESS_DENOM1MAX_PID_PROCESS_DENOM
2useContinuousUpdateU81
3motorProtocolU81
4motorPwmRateU162
6motorIdleU16270002000
8(value)U81DEPRECATED: gyro_use_32kHz
9motorInversionU81
10(value)U81deprecated gyro_to_use
11gyro_high_fsrU810lookup: TABLE_OFF_ON
12gyroMovementCalibrationThresholdU81480200
13gyroCalibrationDurationU162125503000
15gyro_offset_yawU1620-10001000
17checkOverflowU81GYRO_OVERFLOW_CHECK_ALL_AXESlookup: TABLE_GYRO_OVERFLOW_CHECK
18debug_modeU81DEBUG_MODElookup: TABLE_DEBUG
19(value)U81

MSP_SET_ADVANCED_CONFIG — 91 — to FC

Set advanced configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81was gyroConfigMutable()->gyro_sync_denom - removed in API 1.43
1pid_process_denomU81DEFAULT_PID_PROCESS_DENOM1MAX_PID_PROCESS_DENOM
2(read)U81deprecated/ignored
3(read)U81deprecated/ignored
4(read)U162
6motorIdleU16270002000
8(read)U81DEPRECATED: gyro_use_32khz
9(read)U81deprecated/ignored
10(read)U81deprecated gyro_to_use
11gyro_high_fsrU810lookup: TABLE_OFF_ON
12gyroMovementCalibrationThresholdU81480200
13gyroCalibrationDurationU162125503000
15gyro_offset_yawU1620-10001000
17checkOverflowU81GYRO_OVERFLOW_CHECK_ALL_AXESlookup: TABLE_GYRO_OVERFLOW_CHECK
18debug_modeU81DEBUG_MODElookup: TABLE_DEBUG

MSP_FILTER_CONFIG — 92 — from FC

Get filter configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0gyro_lpf1_static_hzU812500LPF_MAX_HZ
1dterm_lpf1_static_hzU1620LPF_MAX_HZ
3yaw_lowpass_hzU1620500
5gyro_soft_notch_hz_1U16200LPF_MAX_HZ
7gyro_soft_notch_cutoff_1U16200LPF_MAX_HZ
9dterm_notch_hzU1620LPF_MAX_HZ
11dterm_notch_cutoffU1620LPF_MAX_HZ
13gyro_soft_notch_hz_2U16200LPF_MAX_HZ
15gyro_soft_notch_cutoff_2U16200LPF_MAX_HZ
17dterm_lpf1_typeU81lookup: TABLE_DTERM_LPF_TYPE
18gyro_hardware_lpfU81GYRO_HARDWARE_LPF_NORMALlookup: TABLE_GYRO_HARDWARE_LPF
19(value)U81DEPRECATED: gyro_32khz_hardware_lpf
20gyro_lpf1_static_hzU1622500LPF_MAX_HZ
22gyro_lpf2_static_hzU1625000LPF_MAX_HZ
24gyro_lpf1_typeU81FILTER_PT1lookup: TABLE_GYRO_LPF_TYPE
25gyro_lpf2_typeU81FILTER_PT1lookup: TABLE_GYRO_LPF_TYPE
26dterm_lpf2_static_hzU1620LPF_MAX_HZ
28dterm_lpf2_typeU81lookup: TABLE_DTERM_LPF_TYPE
29gyro_lpf1_dyn_min_hzU1622500DYN_LPF_MAX_HZ
31gyro_lpf1_dyn_max_hzU1625000DYN_LPF_MAX_HZ
33dterm_lpf1_dyn_min_hzU1620DYN_LPF_MAX_HZ
35dterm_lpf1_dyn_max_hzU1620DYN_LPF_MAX_HZ
37(value)U162deprecated/padding
39(value)U162deprecated/padding
41(value)U162deprecated/padding
43(value)U162deprecated/padding
45(value)U81DEPRECATED 1.43: dyn_notch_range
46(value)U81DEPRECATED 1.44: dyn_notch_width_percent
47dyn_notch_qU16230011000
49dyn_notch_min_hzU16210020250
51(value)U81deprecated/padding
52(value)U81deprecated/padding
53(value)U162deprecated/padding
55(value)U162deprecated/padding
57rpm_filter_harmonicsU81303
58rpm_filter_min_hzU8110030200
59(value)U81deprecated/padding
60(value)U81deprecated/padding
61dyn_notch_max_hzU1626002001000
63(value)U162deprecated/padding
65dterm_lpf1_dyn_expoU81010
66(value)U81deprecated/padding
67dyn_notch_countU8130DYN_NOTCH_COUNT_MAX
68(value)U81deprecated/padding
69rpm_filter_fade_range_hzU1625001000
71rpm_filter_qU1625002503000
73(value)U81
74(value)U162deprecated/padding
76(value)U162deprecated/padding
78(value)U81deprecated/padding

MSP_SET_FILTER_CONFIG — 93 — to FC

Set filter configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0gyro_lpf1_static_hzU812500LPF_MAX_HZ
1dterm_lpf1_static_hzU1620LPF_MAX_HZ
3yaw_lowpass_hzU1620500
5gyro_soft_notch_hz_1U16200LPF_MAX_HZ
7gyro_soft_notch_cutoff_1U16200LPF_MAX_HZ
9dterm_notch_hzU1620LPF_MAX_HZ
11dterm_notch_cutoffU1620LPF_MAX_HZ
13gyro_soft_notch_hz_2U16200LPF_MAX_HZ
15gyro_soft_notch_cutoff_2U16200LPF_MAX_HZ
17dterm_lpf1_typeU81lookup: TABLE_DTERM_LPF_TYPE
18gyro_hardware_lpfU81GYRO_HARDWARE_LPF_NORMALlookup: TABLE_GYRO_HARDWARE_LPF
19(read)U81DEPRECATED: gyro_32khz_hardware_lpf
20gyro_lpf1_static_hzU1622500LPF_MAX_HZ
22gyro_lpf2_static_hzU1625000LPF_MAX_HZ
24gyro_lpf1_typeU81FILTER_PT1lookup: TABLE_GYRO_LPF_TYPE
25gyro_lpf2_typeU81FILTER_PT1lookup: TABLE_GYRO_LPF_TYPE
26dterm_lpf2_static_hzU1620LPF_MAX_HZ
28dterm_lpf2_typeU81lookup: TABLE_DTERM_LPF_TYPE
29gyro_lpf1_dyn_min_hzU1622500DYN_LPF_MAX_HZ
31gyro_lpf1_dyn_max_hzU1625000DYN_LPF_MAX_HZ
33dterm_lpf1_dyn_min_hzU1620DYN_LPF_MAX_HZ
35dterm_lpf1_dyn_max_hzU1620DYN_LPF_MAX_HZ
37(read)U162
39(read)U162
41(read)U162
43(read)U162
45(read)U81DEPRECATED 1.43: dyn_notch_range
46(read)U81DEPRECATED 1.44: dyn_notch_width_percent
47dyn_notch_qU16230011000
49dyn_notch_min_hzU16210020250
51(read)U81deprecated/ignored
52(read)U81deprecated/ignored
53(read)U162
55(read)U162
57rpm_filter_harmonicsU81303
58rpm_filter_min_hzU8110030200
59(read)U81deprecated/ignored
60(read)U81deprecated/ignored
61dyn_notch_max_hzU1626002001000
63(read)U162
65dterm_lpf1_dyn_expoU81010
66(read)U81deprecated/ignored
67(read)U81deprecated/ignored
68(read)U81deprecated/ignored
69(read)U162
71(read)U162
73(read)U81deprecated/ignored
74(read)U162
76(read)U162
78(read)U81deprecated/ignored

MSP_PID_ADVANCED — 94 — from FC

Get advanced PID settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162deprecated/padding
2(value)U162deprecated/padding
4(value)U162was pidProfile.yaw_p_limit
6(value)U81reserved
7(value)U81was vbatPidCompensation
8feedforward_transitionU810100
9(value)U81deprecated/padding
10(value)U81was low byte of currentPidProfile->dtermSetpointWeight
11(value)U81reserved
12(value)U81reserved
13(value)U81reserved
14rateAccelLimitU1620500
16yawRateAccelLimitU1620500
18angle_limitU811080
19(value)U81was pidProfile.levelSensitivity
20(value)U162was currentPidProfile->itermThrottleThreshold
22anti_gravity_gainU162ITERM_ACCELERATOR_GAIN_OFFITERM_ACCELERATOR_GAIN_MAX
24(value)U162was currentPidProfile->dtermSetpointWeight
26iterm_rotationU81lookup: TABLE_OFF_ON
27(value)U81was currentPidProfile->smart_feedforward
28iterm_relaxU81lookup: TABLE_ITERM_RELAX
29iterm_relax_typeU81lookup: TABLE_ITERM_RELAX_TYPE
30(value)U81deprecated/padding
31(value)U81deprecated/padding
32(value)U81was abs_control_gain
33throttle_boostU810100
34(value)U81deprecated/padding
35acro_trainer_angle_limitU811080
36(value)U81deprecated/padding
37FU162
39FU162
41FU162
43(value)U81was currentPidProfile->antiGravityMode
44(value)U81
45(value)U81
46(value)U81
47d_max_gainU810100
48d_max_advanceU810200
49(value)U81deprecated/padding
50(value)U81deprecated/padding
51(value)U81deprecated/padding
52(value)U81deprecated/padding
53(value)U81deprecated/padding
54use_integrated_yawU81lookup: TABLE_OFF_ON
55integrated_yaw_relaxU810255
56(value)U81deprecated/padding
57(value)U81deprecated/padding
58iterm_relax_cutoffU81150
59(value)U81deprecated/padding
60motor_output_limitU81MOTOR_OUTPUT_LIMIT_PERCENT_MINMOTOR_OUTPUT_LIMIT_PERCENT_MAX
61auto_profile_cell_countU81AUTO_PROFILE_CELL_COUNT_CHANGEMAX_AUTO_DETECT_CELL_COUNT
62dyn_idle_min_rpmU810200
63(value)U81deprecated/padding
64feedforward_averagingU81lookup: TABLE_FEEDFORWARD_AVERAGING
65feedforward_smooth_factorU81095
66feedforward_boostU81050
67feedforward_max_rate_limitU810200
68feedforward_jitter_factorU81020
69(value)U81deprecated/padding
70(value)U81deprecated/padding
71(value)U81deprecated/padding
72(value)U81deprecated/padding
73(value)U81deprecated/padding
74vbat_sag_compensationU810150
75(value)U81deprecated/padding
76thrustLinearizationU810150
77(value)U81deprecated/padding
78tpa_modeU81lookup: TABLE_TPA_MODE
79tpa_rateU810TPA_MAX
80tpa_breakpointU162PWM_RANGE_MINPWM_RANGE_MAXwas currentControlRateProfile->tpa_breakpoint

MSP_SET_PID_ADVANCED — 95 — to FC

Set advanced PID settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162
2(read)U162
4(read)U162was pidProfile.yaw_p_limit
6(read)U81reserved
7(read)U81was vbatPidCompensation
8feedforward_transitionU810100
9(read)U81deprecated/ignored
10(read)U81was low byte of currentPidProfile->dtermSetpointWeight
11(read)U81reserved
12(read)U81reserved
13(read)U81reserved
14rateAccelLimitU1620500
16yawRateAccelLimitU1620500
18angle_limitU811080
19(read)U81was pidProfile.levelSensitivity
20(read)U162was currentPidProfile->itermThrottleThreshold
22anti_gravity_gainU162ITERM_ACCELERATOR_GAIN_OFFITERM_ACCELERATOR_GAIN_MAX
24(read)U162was currentPidProfile->dtermSetpointWeight
26iterm_rotationU81lookup: TABLE_OFF_ON
27(read)U81was currentPidProfile->smart_feedforward
28iterm_relaxU81lookup: TABLE_ITERM_RELAX
29iterm_relax_typeU81lookup: TABLE_ITERM_RELAX_TYPE
30(read)U81deprecated/ignored
31(read)U81deprecated/ignored
32(read)U81was abs_control_gain
33throttle_boostU810100
34(read)U81deprecated/ignored
35acro_trainer_angle_limitU811080
36(read)U81deprecated/ignored
37(read)U162
39(read)U162
41(read)U162
43(read)U81was currentPidProfile->antiGravityMode
44(read)U81deprecated/ignored
45(read)U81deprecated/ignored
46(read)U81deprecated/ignored
47d_max_gainU810100
48d_max_advanceU810200
49(read)U81deprecated/ignored
50(read)U81deprecated/ignored
51(read)U81deprecated/ignored
52(read)U81deprecated/ignored
53(read)U81deprecated/ignored
54use_integrated_yawU81lookup: TABLE_OFF_ON
55integrated_yaw_relaxU810255
56(read)U81deprecated/ignored
57(read)U81deprecated/ignored
58iterm_relax_cutoffU81150
59(read)U81deprecated/ignored
60motor_output_limitU81MOTOR_OUTPUT_LIMIT_PERCENT_MINMOTOR_OUTPUT_LIMIT_PERCENT_MAX
61auto_profile_cell_countU81AUTO_PROFILE_CELL_COUNT_CHANGEMAX_AUTO_DETECT_CELL_COUNT
62dyn_idle_min_rpmU810200
63(read)U81deprecated/ignored
64(read)U81deprecated/ignored
65feedforward_smooth_factorU81095
66feedforward_boostU81050
67feedforward_max_rate_limitU810200
68feedforward_jitter_factorU81020
69(read)U81deprecated/ignored
70(read)U81deprecated/ignored
71(read)U81deprecated/ignored
72(read)U81deprecated/ignored
73(read)U81deprecated/ignored
74vbat_sag_compensationU810150
75(read)U81deprecated/ignored
76thrustLinearizationU810150
77(read)U81deprecated/ignored
78tpa_modeU81lookup: TABLE_TPA_MODE
79(read)U81deprecated/ignored
80tpa_breakpointU162PWM_RANGE_MINPWM_RANGE_MAX

MSP_SENSOR_CONFIG — 96 — from FC

Get sensor configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0acc_hardwareU81lookup: TABLE_ACC_HARDWARE
1(value)U81
2baro_hardwareU81DEFAULT_BARO_DEVICElookup: TABLE_BARO_HARDWARE
3(value)U81
4mag_hardwareU81MAG_DEFAULTlookup: TABLE_MAG_HARDWARE
5(value)U81
6rangefinder_hardwareU81RANGEFINDER_NONElookup: TABLE_RANGEFINDER_HARDWARE; no RANGEFINDER_DEFAULT value
7(value)U81
8opticalflow_hardwareU81OPTICALFLOW_NONElookup: TABLE_OPTICALFLOW_HARDWARE
9(value)U81

MSP_SET_SENSOR_CONFIG — 97 — to FC

Set sensor configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0acc_hardwareU81lookup: TABLE_ACC_HARDWARE
1(read)U81deprecated/ignored
2baro_hardwareU81DEFAULT_BARO_DEVICElookup: TABLE_BARO_HARDWARE
3(read)U81deprecated/ignored
4mag_hardwareU81MAG_DEFAULTlookup: TABLE_MAG_HARDWARE
5(read)U81deprecated/ignored
6rangefinder_hardwareU81RANGEFINDER_NONElookup: TABLE_RANGEFINDER_HARDWARE
7(read)U81deprecated/ignored
8opticalflow_hardwareU81OPTICALFLOW_NONElookup: TABLE_OPTICALFLOW_HARDWARE
9(read)U81deprecated/ignored

MSP_CAMERA_CONTROL — 98 — both

Camera control

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored

MSP_SET_ARMING_DISABLED — 99 — to FC

Enable/disable arming

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored

MSP_STATUS — 101 — from FC

Cycletime & errors_count & sensor present & box activation & current setting number

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162
2(value)U162
4(value)U162deprecated/padding
6(value)U162
8(variable data)bytes?unconditional part of flags, first 32 bits
?(value)U81
?(value)U162
?(value)U81
?(value)U81
?(value)U162gyro cycle time
?(value)U81
?(variable data)bytes?variable-length data
?(value)U81
?(value)U324
?(value)U81
?(value)U162
?(value)U162deprecated/padding
?(value)U81
?(value)U81
?(value)U81

MSP_RAW_IMU — 102 — from FC

9 DOF

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162
2(value)U162deprecated/padding
4(value)U162
6(value)U162
8(value)U162deprecated/padding

MSP_SERVO — 103 — from FC

Servos

OffsetFieldTypeBytesDefaultMinMaxNotes
0(variable data)bytes?variable-length data

MSP_MOTOR — 104 — from FC

Motors

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162deprecated/padding
2(value)U162
4(value)U162deprecated/padding

MSP_RC — 105 — from FC

RC channels and more

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162

MSP_RAW_GPS — 106 — from FC

Fix, numsat, lat, lon, alt, speed, ground course

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1numSatU81
2latU324
6lonU324
10(value)U162alt changed from 1m to 0.01m per lsb since MSP API 1.39 by RTH. To maintain backwards compatibility compensate to 1m per lsb in MSP again.
12groundSpeedU162
14groundCourseU162
16pdopU162

MSP_COMP_GPS — 107 — from FC

Distance home, direction home

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162
2(value)U162resolution increased in Betaflight 4.4 by factor of 10, this maintains backwards compatibility for DJI OSD
4(value)U81

MSP_ATTITUDE — 108 — from FC

2 angles 1 heading

OffsetFieldTypeBytesDefaultMinMaxNotes
0rollU162
2pitchU162
4(value)U162

MSP_ALTITUDE — 109 — from FC

Altitude, variometer

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U324
4(value)U162
6(value)U162deprecated/padding

MSP_ANALOG — 110 — from FC

Vbat, powermetersum, rssi if available on RX

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U162milliamp hours drawn from battery
3(value)U162
5(value)U162send current in 0.01 A steps, range is -320A to 320A
7(value)U162

MSP_RC_TUNING — 111 — from FC

RC rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81R,P,Y see flight_dynamics_index_t
3(value)U81was currentControlRateProfile->tpa_rate
4thrMid8U810100
5thrExpo8U810100
6(value)U162was currentControlRateProfile->tpa_breakpoint
8(value)U81
9(value)U81
10(value)U81
11(value)U81
12throttle_limit_typeU81lookup: TABLE_THROTTLE_LIMIT_TYPE
13throttle_limit_percentU8125100
14(value)U162
16(value)U162
18(value)U162
20rates_typeU81lookup: TABLE_RATES_TYPE
21thrHover8U810100

MSP_PID — 112 — from FC

P I D coeff (9 are used currently)

OffsetFieldTypeBytesDefaultMinMaxNotes
0PU81
1IU81
2DU81

MSP_PIDNAMES — 117 — from FC

The PID names

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81

MSP_SERVO_CONFIGURATIONS — 120 — from FC

All servo configurations

OffsetFieldTypeBytesDefaultMinMaxNotes
0minU162
2maxU162
4middleU162
6rateU81
7forwardFromChannelU81
8reversedSourcesU324

MSP_MOTOR_3D_CONFIG — 124 — from FC

Settings needed for reversible ESCs

OffsetFieldTypeBytesDefaultMinMaxNotes
0deadband3d_lowU1621406PWM_PULSE_MINPWM_RANGE_MIDDLE
2deadband3d_highU1621514PWM_RANGE_MIDDLEPWM_PULSE_MAX
4neutral3dU1621460PWM_PULSE_MINPWM_PULSE_MAX

MSP_RC_DEADBAND — 125 — from FC

Deadbands for yaw alt pitch roll

OffsetFieldTypeBytesDefaultMinMaxNotes
0deadbandU810032
1yaw_deadbandU8100100
2deadbandU810032
3(value)U81deprecated/padding
4deadband3d_throttleU162501100

MSP_SENSOR_ALIGNMENT — 126 — from FC

Orientation of acc,gyro,mag

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81Starting with 4.0 gyro and acc alignment are the same
2mag_alignmentU81MAG_ALIGNlookup: TABLE_ALIGNMENT
3(value)U81deprecated/padding
4(value)U81
5gyro_enabled_bitmaskU81DEFAULT_GYRO_ENABLEDdeprecates gyro_to_use
6rollU162
8pitchU162
10yawU162
12(value)U162deprecated/padding
14(value)U162deprecated/padding
16(value)U162deprecated/padding

MSP_LED_STRIP_MODECOLOR — 127 — from FC

Get LED strip mode_color settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81
3(value)U81
4(value)U81
5(value)U81
6(value)U81
7(value)U81deprecated/padding
8ledstrip_aux_channelU81THROTTLE

MSP_VOLTAGE_METERS — 128 — from FC

Voltage (per meter)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81

MSP_CURRENT_METERS — 129 — from FC

Amperage (per meter)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U162milliamp hours drawn from battery
3(value)U162send amperage in 0.001 A steps (mA). Negative range is truncated to zero

MSP_BATTERY_STATE — 130 — from FC

Connected/Disconnected, Voltage, Current Used

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U810 indicates battery not detected.
1batteryCapacityU162020000in mAh
3(value)U81in 0.1V steps
4(value)U162milliamp hours drawn from battery
6(value)U162send current in 0.01 A steps, range is -320A to 320A
8(value)U81
9(value)U162in 0.01V steps

MSP_MOTOR_CONFIG — 131 — from FC

Motor configuration (min/max throttle, etc)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162was minthrottle until after 4.5
2maxthrottleU1622000PWM_PULSE_MINPWM_PULSE_MAX
4mincommandU1621000PWM_PULSE_MINPWM_PULSE_MAX
6(value)U81
7motorPoleCountU81144UINT8_MAX
8(value)U81
9(value)U81deprecated/padding
10(value)U81ESC sensor available
11(value)U81deprecated/padding

MSP_GPS_CONFIG — 132 — from FC

GPS configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0providerU81GPS_VIRTUALlookup: TABLE_GPS_PROVIDER
1sbasModeU81SBAS_NONElookup: TABLE_GPS_SBAS_MODE
2autoConfigU81GPS_AUTOCONFIG_ONlookup: TABLE_OFF_ON
3autoBaudU81GPS_AUTOBAUD_OFFlookup: TABLE_OFF_ON
4gps_set_home_point_onceU810lookup: TABLE_OFF_ON
5gps_ublox_use_galileoU810lookup: TABLE_OFF_ON

MSP_COMPASS_CONFIG — 133 — from FC

Compass configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0mag_declinationU1620-300300

MSP_ESC_SENSOR_DATA — 134 — from FC

Extra ESC data from 32-Bit ESCs (Temperature, RPM)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1temperatureU81
2rpmU162
4(value)U81
5(value)U81
6(value)U162

MSP_GPS_RESCUE — 135 — from FC

GPS Rescue angle, returnAltitude, descentDistance, groundSpeed, sanityChecks and minSats

OffsetFieldTypeBytesDefaultMinMaxNotes
0maxRescueAngleU162453060
2returnAltitudeMU1623051000
4descentDistanceMU1622010500
6groundSpeedCmSU16275003000
8throttleMinU162110010501400
10throttleMaxU162190014002000
12hoverThrottleU162127501700
14sanityChecksU81RESCUE_SANITY_FS_ONLYlookup: TABLE_GPS_RESCUE_SANITY_CHECK
15minSatsU818550
16ascendRateU162750502500
18descendRateU16215025500
20allowArmingWithoutFixU810lookup: TABLE_OFF_ON
21altitudeModeU81GPS_RESCUE_ALT_MODE_MAXlookup: TABLE_GPS_RESCUE_ALT_MODE
22minStartDistMU162151030
24initialClimbMU162100100

MSP_GPS_RESCUE_PIDS — 136 — from FC

GPS Rescue throttleP and velocity PIDS + yaw P

OffsetFieldTypeBytesDefaultMinMaxNotes
0altitudePU162150200
2altitudeIU162150200
4altitudeDU162150200
6velPU16280200
8velIU162400200
10velDU162120200
12yawPU162500200

MSP_VTXTABLE_BAND — 137 — from FC

VTX table band/channel data

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81band number (same as request)
1(value)U81band name length
2(value)U81
3(value)U81band letter
4(value)U81CUSTOM = 0; FACTORY = 1
5channelsU810number of channel frequencies to follow
6(value)U162

MSP_VTXTABLE_POWERLEVEL — 138 — from FC

VTX table powerLevel data

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81powerLevel number (same as request)
1(value)U162
3(value)U81powerLevel label length
4(value)U81

MSP_MOTOR_TELEMETRY — 139 — from FC

Per-motor telemetry data (RPM, packet stats, ESC temp, etc.)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U324
5(value)U162
7(value)U81
8(value)U162
10(value)U162
12(value)U162

MSP_VALIDATE_SIMPLIFIED_TUNING — 145 — from FC

Returns array of true/false showing which simplified tuning groups match values

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81

MSP_UID — 160 — from FC

Unique device ID

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U324
4(value)U324
8(value)U324

MSP_GPSSVINFO — 164 — from FC

Get Signal Strength (only U-Blox)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1chnU81
2svidU81
3qualityU81
4cnoU81

MSP_ATTITUDE_QUATERNION — 167 — from FC

Orientation quaternion components (w, x, y, z)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162
2(value)U162
4(value)U162
6(value)U162

MSP_COPY_PROFILE — 183 — to FC

Copy settings between profiles

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U810 = pid profile, 1 = control rate profile
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored

MSP_BEEPER_CONFIG — 184 — from FC

Get beeper configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0beeper_off_flagsU324DEFAULT_BEEPER_OFF_FLAGS
4dshotBeaconToneU8111DSHOT_CMD_BEACON5
5dshotBeaconOffFlagsU324DEFAULT_DSHOT_BEACON_OFF_FLAGS

MSP_SET_BEEPER_CONFIG — 185 — to FC

Set beeper configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0beeper_off_flagsU324DEFAULT_BEEPER_OFF_FLAGS
4dshotBeaconToneU8111DSHOT_CMD_BEACON5
5dshotBeaconOffFlagsU324DEFAULT_DSHOT_BEACON_OFF_FLAGS

MSP_SET_TX_INFO — 186 — to FC

Set runtime information from TX lua scripts

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored

MSP_TX_INFO — 187 — from FC

Get runtime information for TX lua scripts

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81

MSP_SET_OSD_CANVAS — 188 — to FC

Set OSD canvas size COLSxROWS

OffsetFieldTypeBytesDefaultMinMaxNotes
0canvas_colsU8153063
1canvas_rowsU8120031

MSP_OSD_CANVAS — 189 — from FC

Get OSD canvas size COLSxROWS

OffsetFieldTypeBytesDefaultMinMaxNotes
0canvas_colsU8153063
1canvas_rowsU8120031

MSP_SET_RAW_RC — 200 — to FC

8 rc chan

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162

MSP_SET_RAW_GPS — 201 — to FC

Fix, numsat, lat, lon, alt, speed

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U324
6(read)U324
10(read)U162alt changed from 1m to 0.01m per lsb since MSP API 1.39 by RTH. Received MSP altitudes in 1m per lsb have to upscaled.
12(read)U162

MSP_SET_PID — 202 — to FC

P I D coeff (9 are used currently)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored

MSP_SET_RC_TUNING — 204 — to FC

RC rate, rc expo, rollpitch rate, yaw rate, dyn throttle PID, yaw expo

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored
3(read)U81tpa_rate is moved to PID profile
4thrMid8U810100
5thrExpo8U810100
6(read)U162tpa_breakpoint is moved to PID profile
8(read)U81deprecated/ignored
9(read)U81deprecated/ignored
10(read)U81deprecated/ignored
11(read)U81deprecated/ignored
12throttle_limit_typeU81lookup: TABLE_THROTTLE_LIMIT_TYPE
13throttle_limit_percentU8125100
14(read)U162
16(read)U162
18(read)U162
20rates_typeU81lookup: TABLE_RATES_TYPE
21thrHover8U810100

MSP_RESET_CONF — 208 — to FC

No param - reset settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81

MSP_SELECT_SETTING — 210 — to FC

Select setting number (0-2)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored

MSP_SET_HEADING — 211 — to FC

Define a new heading hold direction

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162

MSP_SET_SERVO_CONFIGURATION — 212 — to FC

Servo settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U162
3(read)U162
5(read)U162
7(read)U81deprecated/ignored
8(read)U81deprecated/ignored
9(read)U324

MSP_SET_MOTOR — 214 — to FC

PropBalance function

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162

MSP_SET_MOTOR_3D_CONFIG — 217 — to FC

Settings needed for reversible ESCs

OffsetFieldTypeBytesDefaultMinMaxNotes
0deadband3d_lowU1621406PWM_PULSE_MINPWM_RANGE_MIDDLE
2deadband3d_highU1621514PWM_RANGE_MIDDLEPWM_PULSE_MAX
4neutral3dU1621460PWM_PULSE_MINPWM_PULSE_MAX

MSP_SET_RC_DEADBAND — 218 — to FC

Deadbands for yaw alt pitch roll

OffsetFieldTypeBytesDefaultMinMaxNotes
0deadbandU810032
1yaw_deadbandU8100100
2deadbandU810032
3(read)U81deprecated/ignored
4deadband3d_throttleU162501100

MSP_SET_SENSOR_ALIGNMENT — 220 — to FC

Set the orientation of acc,gyro,mag

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81discard deprecated acc_align
2mag_alignmentU81MAG_ALIGNlookup: TABLE_ALIGNMENT
3(read)U81deprecated/ignored
4gyro_enabled_bitmaskU81DEFAULT_GYRO_ENABLED
5(read)U162
7(read)U162
9(read)U162
11(read)U162
13(read)U162
15(read)U162

MSP_SET_LED_STRIP_MODECOLOR — 221 — to FC

Set LED strip mode_color settings

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored

MSP_SET_MOTOR_CONFIG — 222 — to FC

Motor configuration (min/max throttle, etc)

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162minthrottle deprecated in 4.6
2maxthrottleU1622000PWM_PULSE_MINPWM_PULSE_MAX
4mincommandU1621000PWM_PULSE_MINPWM_PULSE_MAX
6motorPoleCountU81144UINT8_MAX
7(read)U81deprecated/ignored
8(read)U81deprecated/ignored

MSP_SET_GPS_CONFIG — 223 — to FC

GPS configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0providerU81GPS_VIRTUALlookup: TABLE_GPS_PROVIDER
1sbasModeU81SBAS_NONElookup: TABLE_GPS_SBAS_MODE
2autoConfigU81GPS_AUTOCONFIG_ONlookup: TABLE_OFF_ON
3autoBaudU81GPS_AUTOBAUD_OFFlookup: TABLE_OFF_ON
4gps_set_home_point_onceU810lookup: TABLE_OFF_ON
5gps_ublox_use_galileoU810lookup: TABLE_OFF_ON

MSP_SET_COMPASS_CONFIG — 224 — to FC

Compass configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0mag_declinationU1620-300300

MSP_SET_GPS_RESCUE — 225 — to FC

Set GPS Rescue parameters

OffsetFieldTypeBytesDefaultMinMaxNotes
0maxRescueAngleU162453060
2returnAltitudeMU1623051000
4descentDistanceMU1622010500
6groundSpeedCmSU16275003000
8throttleMinU162110010501400
10throttleMaxU162190014002000
12hoverThrottleU162127501700
14sanityChecksU81RESCUE_SANITY_FS_ONLYlookup: TABLE_GPS_RESCUE_SANITY_CHECK
15minSatsU818550
16ascendRateU162750502500
18descendRateU16215025500
20allowArmingWithoutFixU810lookup: TABLE_OFF_ON
21altitudeModeU81GPS_RESCUE_ALT_MODE_MAXlookup: TABLE_GPS_RESCUE_ALT_MODE
22minStartDistMU162151030
24initialClimbMU162100100

MSP_SET_GPS_RESCUE_PIDS — 226 — to FC

Set GPS Rescue PID values

OffsetFieldTypeBytesDefaultMinMaxNotes
0altitudePU162150200
2altitudeIU162150200
4altitudeDU162150200
6velPU16280200
8velIU162400200
10velDU162120200
12yawPU162500200

MSP_SET_VTXTABLE_BAND — 227 — to FC

Set vtxTable band/channel data

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored
3(read)U81deprecated/ignored
4(read)U81deprecated/ignored
5(read)U81deprecated/ignored
6(read)U162

MSP_SET_VTXTABLE_POWERLEVEL — 228 — to FC

Set vtxTable powerLevel data

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U162
3(read)U81deprecated/ignored
4(read)U81deprecated/ignored

MSP_MODE_RANGES_EXTRA — 238 — from FC

Extra mode range data

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81prepend number of EXTRAs array elements
1permanentIdU81each element is aligned with MODE_RANGES by the permanentId
2modeLogicU81
3permanentIdU81

MSP_SET_ACC_TRIM — 239 — to FC

Set acc angle trim values

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U162
2(read)U162

MSP_ACC_TRIM — 240 — from FC

Get acc angle trim values

OffsetFieldTypeBytesDefaultMinMaxNotes
0pitchU162
2rollU162

MSP_SERVO_MIX_RULES — 241 — from FC

Get servo mixer configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0targetChannelU81
1inputSourceU81
2rateU81
3speedU81
4minU81
5maxU81
6boxU81

MSP_SET_SERVO_MIX_RULE — 242 — to FC

Set servo mixer configuration

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored
3(read)U81deprecated/ignored
4(read)U81deprecated/ignored
5(read)U81deprecated/ignored
6(read)U81deprecated/ignored
7(read)U81deprecated/ignored

MSP_SET_RTC — 246 — to FC

Set the RTC clock

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U324
4(read)U162

MSP_RTC — 247 — from FC

Get the RTC clock

OffsetFieldTypeBytesDefaultMinMaxNotes
0yearU162
2monthU81
3dayU81
4hoursU81
5minutesU81
6secondsU81
7millisU162

MSP_SET_BOARD_INFO — 248 — to FC

Set the board information

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored

MSP_DEBUG — 254 — from FC

debug1,debug2,debug3,debug4

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U1624 variables are here for general monitoring purpose

MSP2_COMMON_SERIAL_CONFIG — 0x1009 — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1identifierU81
2functionMaskU324
6msp_baudrateIndexU81
7gps_baudrateIndexU81
8telemetry_baudrateIndexU81
9blackbox_baudrateIndexU81

MSP2_COMMON_SET_SERIAL_CONFIG — 0x100a — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2functionMaskU324
6msp_baudrateIndexU81
7gps_baudrateIndexU81
8telemetry_baudrateIndexU81
9blackbox_baudrateIndexU81
10(read)U81deprecated/ignored

MSP2_SENSOR_GPS — 0x1f03 — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81instance
1(read)U162gps_week
3(read)U324ms_tow
7(read)U81fix_type
8(read)U81satellites_in_view
9(read)U162horizontal_pos_accuracy - convert cm to mm
11(read)U162vertical_pos_accuracy - convert cm to mm
13(read)U162horizontal_vel_accuracy - convert cm to mm
15(read)U162hdop in 4.4 and earlier, pdop in 4.5 and above
17(read)U324
21(read)U324
25(read)U324alt
29(read)U324ned_vel_north
33(read)U324ned_vel_east
37(read)U324ned_vel_down
41(read)U162incoming value expected to be in centidegrees, output value in decidegrees
43(read)U162true_yaw
45(read)U162year
47(read)U81month
48(read)U81day
49(read)U81hour
50(read)U81min
51(read)U81sec

MSP2_MOTOR_OUTPUT_REORDERING — 0x3001 — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81

MSP2_SET_MOTOR_OUTPUT_REORDERING — 0x3002 — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored

MSP2_SEND_DSHOT_COMMAND — 0x3003 — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored
2(read)U81deprecated/ignored
3(read)U81deprecated/ignored

MSP2_GET_OSD_WARNINGS — 0x3005 — from FC

returns active OSD warning message text

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81see displayPortSeverity_e
1(string)str?string data

MSP2_GET_TEXT — 0x3006 — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(string)str?string data

MSP2_SET_TEXT — 0x3007 — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U81deprecated/ignored

MSP2_GET_LED_STRIP_CONFIG_VALUES — 0x3008 — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0ledstrip_brightnessU811005100
1ledstrip_rainbow_deltaU16200HSV_HUE_MAX
3ledstrip_rainbow_freqU16212012000

MSP2_SET_LED_STRIP_CONFIG_VALUES — 0x3009 — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0ledstrip_brightnessU811005100
1ledstrip_rainbow_deltaU16200HSV_HUE_MAX
3ledstrip_rainbow_freqU16212012000

MSP2_SENSOR_CONFIG_ACTIVE — 0x300a — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81
2(value)U81
3(value)U81
4(value)U81
5(value)U81
6(value)U81
7(value)U81
8(value)U81
9(value)U81
10(value)U81
11(value)U81

MSP2_MCU_INFO — 0x300c — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(string)str?string data

MSP2_GYRO_SENSOR_ACTIVE — 0x300d — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1(value)U81

MSP2_BATTERY_PROFILE — 0x300e — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U81
1vbatmincellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX
3vbatmaxcellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX
5vbatwarningcellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX
7vbatfullcellvoltageU162VBAT_CELL_VOTAGE_RANGE_MINVBAT_CELL_VOTAGE_RANGE_MAX
9batteryCapacityU162020000
11forceBatteryCellCountU81024
12consumptionWarningPercentageU810100

MSP2_SET_BATTERY_PROFILE — 0x300f — to FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(read)U81deprecated/ignored
1(read)U162
3(read)U162
5(read)U162
7(read)U162
9(read)U162
11(read)U81deprecated/ignored
12(read)U81deprecated/ignored

MSP2_CLI_SETTING — 0x3010 — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(variable data)bytes?variable-length data

MSP2_CLI_SETTING_INFO — 0x3011 — from FC

OffsetFieldTypeBytesDefaultMinMaxNotes
0(value)U162placeholder, filled below

Implementation Notes

  • For each MSP_<NAME> (read) there is usually a corresponding MSP_SET_<NAME> (write)
  • API version is negotiated via MSP_API_VERSION (code 1) at connection time
  • MSP v2 Betaflight-specific commands start at 0x3000; cross-firmware common commands at 0x1000
  • For complete payload documentation see MSP Extensions and the firmware source

Further Reading

  • MSP Extensions — detailed payload documentation for selected commands
  • src/main/msp/msp.c — all MSP handler implementations
  • src/main/msp/msp_protocol.h — v1 code definitions
  • src/main/msp/msp_protocol_v2_betaflight.h — Betaflight v2 extensions