diff --git a/docs/development/msp/README.md b/docs/development/msp/README.md index 696e7ab7fc1..833a9f6873c 100644 --- a/docs/development/msp/README.md +++ b/docs/development/msp/README.md @@ -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** @@ -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: @@ -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) @@ -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) ## `MSP_API_VERSION (1 / 0x1)` **Description:** Provides the MSP protocol version and the INAV API version. @@ -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`. ## `MSP_SENSOR_STATUS (151 / 0x97)` **Description:** Provides the hardware status for each individual sensor system. @@ -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`. @@ -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. +## `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. + ## `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`. @@ -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. ## `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. ---- - ## `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 (0–35999). 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. ---- - ## `MSP2_BETAFLIGHT_BIND (12288 / 0x3000)` **Description:** Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2). @@ -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. ## `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| |---|---|---|---| diff --git a/docs/development/msp/gen_docs.sh b/docs/development/msp/gen_docs.sh index cd368cf7f00..84aa852841f 100755 --- a/docs/development/msp/gen_docs.sh +++ b/docs/development/msp/gen_docs.sh @@ -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 diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json index 04a045ad3b9..63f3eb2941b 100644 --- a/docs/development/msp/inav_enums.json +++ b/docs/development/msp/inav_enums.json @@ -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": { @@ -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", @@ -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": { @@ -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", @@ -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", @@ -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", @@ -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", @@ -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", @@ -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", @@ -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)", diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md index b3aabb41467..802e813ab43 100644 --- a/docs/development/msp/inav_enums_ref.md +++ b/docs/development/msp/inav_enums_ref.md @@ -370,7 +370,8 @@ | `ACC_ICM42605` | 8 | | | `ACC_BMI270` | 9 | | | `ACC_LSM6DXX` | 10 | | -| `ACC_FAKE` | 11 | | +| `ACC_ICM45686` | 11 | | +| `ACC_FAKE` | 12 | | | `ACC_MAX` | ACC_FAKE | | --- @@ -1317,6 +1318,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 | | @@ -1346,6 +1350,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` | | | --- @@ -1407,53 +1414,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` @@ -2488,7 +2496,8 @@ | `GYRO_ICM42605` | 8 | | | `GYRO_BMI270` | 9 | | | `GYRO_LSM6DXX` | 10 | | -| `GYRO_FAKE` | 11 | | +| `GYRO_ICM45686` | 11 | | +| `GYRO_FAKE` | 12 | | --- ## `HardwareMotorTypes_e` @@ -2924,7 +2933,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` @@ -3531,8 +3541,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` @@ -3658,6 +3667,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 | | @@ -4819,9 +4829,8 @@ |---|---:|---| | `SD_3016` | 0 | | | `HD_5018` | 1 | | -| `HD_3016` | 2 | | -| `HD_6022` | 3 | | -| `HD_5320` | 4 | | +| `HD_6022` | 2 | | +| `HD_5320` | 3 | | --- ## `resourceOwner_e` @@ -5627,7 +5636,7 @@ --- ## `systemState_e` -> Source: ../../../src/main/fc/fc_init.h +> Source: ../../../src/main/fc/fc_init.c | Enumerator | Value | Condition | |---|---:|---| @@ -5641,7 +5650,7 @@ --- ## `systemState_e` -> Source: ../../../src/main/fc/fc_init.c +> Source: ../../../src/main/fc/fc_init.h | Enumerator | Value | Condition | |---|---:|---| diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index ff3e21a1d69..031f3b14179 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -82a3d2eee9d0d1fe609363a08405ed21 +c9458e9a712b7a4f3bc9333aa7bc3dcb diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index 12d67369bd7..c88be881d50 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -6953,6 +6953,35 @@ "notes": "Requires `USE_CURRENT_METER`/`USE_ADC` for current-related fields; values fall back to zero when unavailable. Capacity fields are reported in the units configured by `batteryMetersConfig()->capacity_unit` (mAh or mWh).", "description": "Provides detailed analog sensor readings, superseding `MSP_ANALOG` with higher precision and additional fields." }, + "MSP2_INAV_GET_LINK_STATS": { + "code": 8451, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "uplinkRSSI_dBm", + "ctype": "uint8_t", + "desc": "Uplink RSSI in dBm, sent as a positive magnitude (`getRSSI()`). For example, 70 means -70dBm.", + "units": "-dBm" + }, + { + "name": "uplinkLQ", + "ctype": "uint8_t", + "desc": "Uplink Link Quality (`rxLinkStatistics.uplinkLQ`)", + "units": "%" + }, + { + "name": "uplinkSNR", + "ctype": "int8_t", + "desc": "Uplink Signal-to-Noise Ratio (`rxLinkStatistics.uplinkSNR`)", + "units": "dB" + } + ] + }, + "notes": "Useful for GCS monitoring of the active RC link quality and signal margin.", + "description": "Provides uplink RC link statistics for monitoring on a GCS." + }, "MSP2_INAV_MISC": { "code": 8195, "mspv": 2, @@ -10943,6 +10972,40 @@ "notes": "All attitude angles are in deci-degrees.", "description": "Provides estimates of current attitude, local NEU position, and velocity." }, + "MSP2_INAV_SET_WP_INDEX": { + "code": 8737, + "mspv": 2, + "request": { + "payload": [ + { + "name": "wp_index", + "ctype": "uint8_t", + "desc": "0-based waypoint index to jump to, relative to the mission start waypoint (`posControl.startWpIndex`)", + "units": "-" + } + ] + }, + "reply": null, + "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.", + "description": "Jumps to a specific waypoint during an active waypoint mission, causing the aircraft to immediately begin navigating toward the new target waypoint." + }, + "MSP2_INAV_SET_CRUISE_HEADING": { + "code": 8739, + "mspv": 2, + "request": { + "payload": [ + { + "name": "heading_centidegrees", + "ctype": "int32_t", + "desc": "Target heading in centidegrees (0-35999). Values are wrapped modulo 36000 before being applied.", + "units": "centidegrees" + } + ] + }, + "reply": null, + "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.", + "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." + }, "MSP2_BETAFLIGHT_BIND": { "code": 12288, "mspv": 2, diff --git a/docs/development/msp/rev b/docs/development/msp/rev index bf0d87ab1b2..7ed6ff82de6 100644 --- a/docs/development/msp/rev +++ b/docs/development/msp/rev @@ -1 +1 @@ -4 \ No newline at end of file +5 diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index b7da917520f..802442ca5b9 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -742,6 +742,12 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, getRSSI()); break; + case MSP2_INAV_GET_LINK_STATS: + sbufWriteU8(dst, (uint8_t)-rxLinkStatistics.uplinkRSSI); + sbufWriteU8(dst, rxLinkStatistics.uplinkLQ); + sbufWriteU8(dst, (uint8_t)rxLinkStatistics.uplinkSNR); + break; + case MSP_LOOP_TIME: sbufWriteU16(dst, gyroConfig()->looptime); break; diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 21ad7e3d135..7d092ed41fd 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -116,6 +116,8 @@ #define MSP2_INAV_CUSTOM_OSD_ELEMENT 0x2101 #define MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS 0x2102 +#define MSP2_INAV_GET_LINK_STATS 0x2103 + #define MSP2_INAV_SERVO_CONFIG 0x2200 #define MSP2_INAV_SET_SERVO_CONFIG 0x2201