Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
56 changes: 35 additions & 21 deletions docs/development/msp/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,8 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i



**JSON file rev: 4**
**JSON file rev: 5
**

**Warning: Verification needed, exercise caution until completely verified for accuracy and cleared, especially for integer signs. Source-based generation/validation is forthcoming. Refer to source for absolute certainty**

Expand Down Expand Up @@ -66,6 +67,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
**variable_len**: Optional boolean, if true, message does not have a predefined fixed length and needs appropriate handling\
**variants**: Optional special case, message has different cases of reply/request. Key/description is not a strict expression or code; just a readable condition\
**not_implemented**: Optional special case, message is not implemented (never or deprecated)\
**replaced_by**: Optional array of MSP message names that replace this command. Present when a command is deprecated and scheduled for removal. Empty array if no replacement is needed\
**notes**: String with details of message

## Data dict fields:
Expand Down Expand Up @@ -403,6 +405,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
[8448 - MSP2_INAV_CUSTOM_OSD_ELEMENTS](#msp2_inav_custom_osd_elements)
[8449 - MSP2_INAV_CUSTOM_OSD_ELEMENT](#msp2_inav_custom_osd_element)
[8450 - MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS](#msp2_inav_set_custom_osd_elements)
[8451 - MSP2_INAV_GET_LINK_STATS](#msp2_inav_get_link_stats)
[8461 - MSP2_INAV_OUTPUT_MAPPING_EXT2](#msp2_inav_output_mapping_ext2)
[8704 - MSP2_INAV_SERVO_CONFIG](#msp2_inav_servo_config)
[8705 - MSP2_INAV_SET_SERVO_CONFIG](#msp2_inav_set_servo_config)
Expand All @@ -411,11 +414,11 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
[8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex)
[8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex)
[8724 - MSP2_INAV_SET_GVAR](#msp2_inav_set_gvar)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[8737 - MSP2_INAV_SET_WP_INDEX](#msp2_inav_set_wp_index)
[8739 - MSP2_INAV_SET_CRUISE_HEADING](#msp2_inav_set_cruise_heading)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
[12289 - MSP2_RX_BIND](#msp2_rx_bind)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[8737 - MSP2_INAV_SET_WP_INDEX](#msp2_inav_set_wp_index)
[8739 - MSP2_INAV_SET_CRUISE_HEADING](#msp2_inav_set_cruise_heading)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
[12289 - MSP2_RX_BIND](#msp2_rx_bind)

## <a id="msp_api_version"></a>`MSP_API_VERSION (1 / 0x1)`
**Description:** Provides the MSP protocol version and the INAV API version.
Expand Down Expand Up @@ -2208,7 +2211,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
| `armingFlags` | `uint16_t` | 2 | Bitmask | Bitmask: Flight controller arming flags (`armingFlags`). Note: Truncated to 16 bits |
| `accCalibAxisFlags` | `uint8_t` | 1 | Bitmask | Bitmask: Accelerometer calibrated axes flags (`accGetCalibrationAxisFlags()`) |

**Notes:** Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements.
**Notes:** Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements. The `accCalibAxisFlags` field is not present in `MSP2_INAV_STATUS` but is available via `MSP_CALIBRATION_DATA`.

## <a id="msp_sensor_status"></a>`MSP_SENSOR_STATUS (151 / 0x97)`
**Description:** Provides the hardware status for each individual sensor system.
Expand Down Expand Up @@ -2275,6 +2278,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
| `hdop` | `uint16_t` | 2 | HDOP * 100 | Horizontal Dilution of Precision (`gpsSol.hdop`) |
| `eph` | `uint16_t` | 2 | cm | Estimated Horizontal Position Accuracy (`gpsSol.eph`) |
| `epv` | `uint16_t` | 2 | cm | Estimated Vertical Position Accuracy (`gpsSol.epv`) |
| `hwVersion` | `uint32_t` | 4 | Version code | GPS hardware version (`gpsState.hwVersion`). Values: 500=UBLOX5, 600=UBLOX6, 700=UBLOX7, 800=UBLOX8, 900=UBLOX9, 1000=UBLOX10, 0=UNKNOWN |

**Notes:** Requires `USE_GPS`.

Expand Down Expand Up @@ -4357,6 +4361,20 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i

**Notes:** Payload length must be (OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1) + (CUSTOM_ELEMENTS_PARTS * 3) + 4 bytes including elementIndex. elementIndex must be < MAX_CUSTOM_ELEMENTS. Each partType must be < CUSTOM_ELEMENT_TYPE_END. Firmware NUL-terminates elementText internally.

## <a id="msp2_inav_get_link_stats"></a>`MSP2_INAV_GET_LINK_STATS (8451 / 0x2103)`
**Description:** Provides uplink RC link statistics for monitoring on a GCS.

**Request Payload:** **None**

**Reply Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
| `uplinkRSSI_dBm` | `uint8_t` | 1 | -dBm | Uplink RSSI in dBm, sent as a positive magnitude (`getRSSI()`). For example, 70 means -70dBm. |
| `uplinkLQ` | `uint8_t` | 1 | % | Uplink Link Quality (`rxLinkStatistics.uplinkLQ`) |
| `uplinkSNR` | `int8_t` | 1 | dB | Uplink Signal-to-Noise Ratio (`rxLinkStatistics.uplinkSNR`) |

**Notes:** Useful for GCS monitoring of the active RC link quality and signal margin.

## <a id="msp2_inav_output_mapping_ext2"></a>`MSP2_INAV_OUTPUT_MAPPING_EXT2 (8461 / 0x210d)`
**Description:** Retrieves the full extended output mapping configuration (timer ID, full 32-bit usage flags, and pin label). Supersedes `MSP2_INAV_OUTPUT_MAPPING_EXT`.

Expand Down Expand Up @@ -4529,33 +4547,29 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
**Notes:** All attitude angles are in deci-degrees.

## <a id="msp2_inav_set_wp_index"></a>`MSP2_INAV_SET_WP_INDEX (8737 / 0x2221)`
**Description:** Jumps to a specific waypoint during an active waypoint mission, causing the aircraft to immediately begin navigating toward the new target waypoint.

**Description:** Jumps to a specific waypoint during an active waypoint mission, causing the aircraft to immediately begin navigating toward the new target waypoint.
**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
| `wp_index` | `uint8_t` | 1 | - | 0-based waypoint index to jump to, relative to the mission start waypoint (`posControl.startWpIndex`) |

**Reply Payload:** **None**
**Reply Payload:** **None**

**Notes:** Returns error if the aircraft is not armed, `NAV_WP_MODE` is not active, or the index is outside the valid mission range (`startWpIndex` to `startWpIndex + waypointCount - 1`). On success, sets `posControl.activeWaypointIndex` to the requested index and fires `NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_JUMP`, transitioning the navigation FSM back to `NAV_STATE_WAYPOINT_PRE_ACTION` so the flight controller re-initialises navigation for the new target.

---

## <a id="msp2_inav_set_cruise_heading"></a>`MSP2_INAV_SET_CRUISE_HEADING (8739 / 0x2223)`
**Description:** Sets the course heading target while Cruise or Course Hold mode is active, causing the aircraft to turn to and maintain the new heading.

**Description:** Sets the course heading target while Cruise or Course Hold mode is active, causing the aircraft to turn to and maintain the new heading.
**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
| `heading_centidegrees` | `int32_t` | 4 | centidegrees | Target heading in centidegrees (035999). Values are wrapped modulo 36000 before being applied. |
| `heading_centidegrees` | `int32_t` | 4 | centidegrees | Target heading in centidegrees (0-35999). Values are wrapped modulo 36000 before being applied. |

**Reply Payload:** **None**
**Reply Payload:** **None**

**Notes:** Returns error if the aircraft is not armed or `NAV_COURSE_HOLD_MODE` is not active. On success, sets both `posControl.cruise.course` and `posControl.cruise.previousCourse` to the normalised value, preventing spurious heading adjustments from `getCruiseHeadingAdjustment()` on the next control cycle.

---

## <a id="msp2_betaflight_bind"></a>`MSP2_BETAFLIGHT_BIND (12288 / 0x3000)`
**Description:** Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2).

Expand All @@ -4566,14 +4580,14 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
**Notes:** Requires `rxConfig()->receiverType == RX_TYPE_SERIAL`. Requires `USE_SERIALRX_CRSF` or `USE_SERIALRX_SRXL2`. Calls `crsfBind()` or `srxl2Bind()` respectively. Returns error if receiver type or provider is not supported for binding.

## <a id="msp2_rx_bind"></a>`MSP2_RX_BIND (12289 / 0x3001)`
**Description:** Initiates binding for MSP receivers (mLRS).

**Description:** Initiates binding for MSP receivers (mLRS).
**Request Payload:**
|Field|C Type|Size (Bytes)|Description|
|---|---|---|---|
| `port_id` | `uint8_t` | 1 | Port ID |
| `reserved_for_custom_use` | `uint8_t[3]` | 3 | Reserved for custom use |

**Reply Payload:**
|Field|C Type|Size (Bytes)|Description|
|---|---|---|---|
Expand Down
2 changes: 1 addition & 1 deletion docs/development/msp/gen_docs.sh
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ expected="$(awk '{print $1}' msp_messages.checksum)"
echo "Hash:" $actual
if [[ "$actual" != "$expected" ]]; then
n="$(cat rev)"
printf '%d' "$(n + 1)" > rev
printf '%d' "$((n + 1))" > rev
echo "File changed, incrementing revision"
echo $actual > msp_messages.checksum
fi
Expand Down
121 changes: 65 additions & 56 deletions docs/development/msp/inav_enums.json
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,8 @@
"ACC_ICM42605": "8",
"ACC_BMI270": "9",
"ACC_LSM6DXX": "10",
"ACC_FAKE": "11",
"ACC_ICM45686": "11",
"ACC_FAKE": "12",
"ACC_MAX": "ACC_FAKE"
},
"accEvent_t": {
Expand Down Expand Up @@ -736,6 +737,9 @@
"CRSF_FRAMETYPE_VARIO_SENSOR": "7",
"CRSF_FRAMETYPE_BATTERY_SENSOR": "8",
"CRSF_FRAMETYPE_BAROMETER_ALTITUDE": "9",
"CRSF_FRAMETYPE_AIRSPEED_SENSOR": "10",
"CRSF_FRAMETYPE_RPM": "12",
"CRSF_FRAMETYPE_TEMP": "13",
"CRSF_FRAMETYPE_LINK_STATISTICS": "20",
"CRSF_FRAMETYPE_RC_CHANNELS_PACKED": "22",
"CRSF_FRAMETYPE_ATTITUDE": "30",
Expand All @@ -760,6 +764,9 @@
"CRSF_FRAME_GPS_INDEX": "",
"CRSF_FRAME_VARIO_SENSOR_INDEX": "",
"CRSF_FRAME_BAROMETER_ALTITUDE_INDEX": "",
"CRSF_FRAME_TEMP_INDEX": "",
"CRSF_FRAME_RPM_INDEX": "",
"CRSF_FRAME_AIRSPEED_INDEX": "",
"CRSF_SCHEDULE_COUNT_MAX": ""
},
"crsrRfMode_e": {
Expand Down Expand Up @@ -801,53 +808,54 @@
"DEVHW_ICM42605": "7",
"DEVHW_BMI270": "8",
"DEVHW_LSM6D": "9",
"DEVHW_MPU9250": "10",
"DEVHW_BMP085": "11",
"DEVHW_BMP280": "12",
"DEVHW_MS5611": "13",
"DEVHW_MS5607": "14",
"DEVHW_LPS25H": "15",
"DEVHW_SPL06": "16",
"DEVHW_BMP388": "17",
"DEVHW_DPS310": "18",
"DEVHW_B2SMPB": "19",
"DEVHW_HMC5883": "20",
"DEVHW_AK8963": "21",
"DEVHW_AK8975": "22",
"DEVHW_IST8310_0": "23",
"DEVHW_IST8310_1": "24",
"DEVHW_IST8308": "25",
"DEVHW_QMC5883": "26",
"DEVHW_QMC5883P": "27",
"DEVHW_MAG3110": "28",
"DEVHW_LIS3MDL": "29",
"DEVHW_RM3100": "30",
"DEVHW_VCM5883": "31",
"DEVHW_MLX90393": "32",
"DEVHW_LM75_0": "33",
"DEVHW_LM75_1": "34",
"DEVHW_LM75_2": "35",
"DEVHW_LM75_3": "36",
"DEVHW_LM75_4": "37",
"DEVHW_LM75_5": "38",
"DEVHW_LM75_6": "39",
"DEVHW_LM75_7": "40",
"DEVHW_DS2482": "41",
"DEVHW_MAX7456": "42",
"DEVHW_SRF10": "43",
"DEVHW_VL53L0X": "44",
"DEVHW_VL53L1X": "45",
"DEVHW_US42": "46",
"DEVHW_TOF10120_I2C": "47",
"DEVHW_TERARANGER_EVO_I2C": "48",
"DEVHW_MS4525": "49",
"DEVHW_DLVR": "50",
"DEVHW_M25P16": "51",
"DEVHW_W25N": "52",
"DEVHW_UG2864": "53",
"DEVHW_SDCARD": "54",
"DEVHW_IRLOCK": "55",
"DEVHW_PCF8574": "56"
"DEVHW_ICM45686": "10",
"DEVHW_MPU9250": "11",
"DEVHW_BMP085": "12",
"DEVHW_BMP280": "13",
"DEVHW_MS5611": "14",
"DEVHW_MS5607": "15",
"DEVHW_LPS25H": "16",
"DEVHW_SPL06": "17",
"DEVHW_BMP388": "18",
"DEVHW_DPS310": "19",
"DEVHW_B2SMPB": "20",
"DEVHW_HMC5883": "21",
"DEVHW_AK8963": "22",
"DEVHW_AK8975": "23",
"DEVHW_IST8310_0": "24",
"DEVHW_IST8310_1": "25",
"DEVHW_IST8308": "26",
"DEVHW_QMC5883": "27",
"DEVHW_QMC5883P": "28",
"DEVHW_MAG3110": "29",
"DEVHW_LIS3MDL": "30",
"DEVHW_RM3100": "31",
"DEVHW_VCM5883": "32",
"DEVHW_MLX90393": "33",
"DEVHW_LM75_0": "34",
"DEVHW_LM75_1": "35",
"DEVHW_LM75_2": "36",
"DEVHW_LM75_3": "37",
"DEVHW_LM75_4": "38",
"DEVHW_LM75_5": "39",
"DEVHW_LM75_6": "40",
"DEVHW_LM75_7": "41",
"DEVHW_DS2482": "42",
"DEVHW_MAX7456": "43",
"DEVHW_SRF10": "44",
"DEVHW_VL53L0X": "45",
"DEVHW_VL53L1X": "46",
"DEVHW_US42": "47",
"DEVHW_TOF10120_I2C": "48",
"DEVHW_TERARANGER_EVO_I2C": "49",
"DEVHW_MS4525": "50",
"DEVHW_DLVR": "51",
"DEVHW_M25P16": "52",
"DEVHW_W25N": "53",
"DEVHW_UG2864": "54",
"DEVHW_SDCARD": "55",
"DEVHW_IRLOCK": "56",
"DEVHW_PCF8574": "57"
},
"deviceFlags_e": {
"_source": "inav/src/main/drivers/bus.h",
Expand Down Expand Up @@ -1527,7 +1535,8 @@
"GYRO_ICM42605": "8",
"GYRO_BMI270": "9",
"GYRO_LSM6DXX": "10",
"GYRO_FAKE": "11"
"GYRO_ICM45686": "11",
"GYRO_FAKE": "12"
},
"HardwareMotorTypes_e": {
"_source": "inav/src/main/drivers/pwm_esc_detect.h",
Expand Down Expand Up @@ -1861,7 +1870,8 @@
"LED_MODE_ANGLE": "3",
"LED_MODE_MAG": "4",
"LED_MODE_BARO": "5",
"LED_SPECIAL": "6"
"LED_MODE_LOITER": "6",
"LED_SPECIAL": "7"
},
"ledOverlayId_e": {
"_source": "inav/src/main/io/ledstrip.h",
Expand Down Expand Up @@ -2325,8 +2335,7 @@
"MULTI_FUNC_3": "3",
"MULTI_FUNC_4": "4",
"MULTI_FUNC_5": "5",
"MULTI_FUNC_6": "6",
"MULTI_FUNC_END": "7"
"MULTI_FUNC_END": "6"
},
"multiFunctionFlags_e": {
"_source": "inav/src/main/fc/multifunction.h",
Expand Down Expand Up @@ -2407,6 +2416,7 @@
"NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_HOLD_TIME": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
"NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_RTH_LAND": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
"NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_3",
"NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_JUMP": "NAV_FSM_EVENT_STATE_SPECIFIC_4",
"NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_INITIALIZE": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
"NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_TRACKBACK": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
"NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_3",
Expand Down Expand Up @@ -3291,9 +3301,8 @@
"_source": "inav/src/main/io/displayport_msp_osd.c",
"SD_3016": "0",
"HD_5018": "1",
"HD_3016": "2",
"HD_6022": "3",
"HD_5320": "4"
"HD_6022": "2",
"HD_5320": "3"
},
"resourceOwner_e": {
"_source": "inav/src/main/drivers/resource.h",
Expand Down Expand Up @@ -3829,7 +3838,7 @@
"THR_HI": "(2 << (2 * THROTTLE))"
},
"systemState_e": {
"_source": "inav/src/main/fc/fc_init.c",
"_source": "inav/src/main/fc/fc_init.h",
"SYSTEM_STATE_INITIALISING": "0",
"SYSTEM_STATE_CONFIG_LOADED": "(1 << 0)",
"SYSTEM_STATE_SENSORS_READY": "(1 << 1)",
Expand Down
Loading
Loading