From b4f55d26d51fdc1ffbf9c9e0c39723cd40c51b59 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 02:24:36 -0500 Subject: [PATCH 1/8] msp set alt test --- docs/development/msp/msp_messages.json | 41 +++++++++++++++++++++ src/main/fc/fc_msp.c | 51 ++++++++++++++++++++++++++ src/main/msp/msp_protocol_v2_inav.h | 4 +- src/main/navigation/navigation.h | 3 +- 4 files changed, 97 insertions(+), 2 deletions(-) diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index dde6d3ecef5..7b79f69767a 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10829,6 +10829,47 @@ "notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).", "description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone." }, + "MSP2_INAV_SET_ALT_TARGET": { + "code": 8725, + "mspv": 2, + "variable_len": true, + "request": { + "payload": [ + { + "name": "altitudeDatum", + "ctype": "uint8_t", + "desc": "Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved)", + "units": "", + "optional": true + }, + { + "name": "altitudeTarget", + "ctype": "int32_t", + "desc": "Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above", + "units": "cm", + "optional": true + } + ] + }, + "reply": { + "payload": [ + { + "name": "altitudeDatum", + "ctype": "uint8_t", + "desc": "Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM`", + "units": "" + }, + { + "name": "altitudeTarget", + "ctype": "int32_t", + "desc": "Current altitude target (`posControl.desiredState.pos.z`)", + "units": "cm" + } + ] + }, + "notes": "Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).", + "description": "Get or set the active altitude hold target." + }, "MSP2_INAV_FULL_LOCAL_POSE": { "code": 8736, "mspv": 2, diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 54c225c78bc..4e387bb3493 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4111,6 +4111,57 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu *ret = mspFcGeozoneVerteciesOutCommand(dst, src); break; #endif + + case MSP2_INAV_SET_ALT_TARGET: + { + const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); + if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) { + *ret = MSP_RESULT_ERROR; + break; + } + + if (dataSize == 0) { + sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM); + sbufWriteU32(dst, (uint32_t)lrintf(posControl.desiredState.pos.z)); + *ret = MSP_RESULT_ACK; + break; + } + + if (dataSize != (sizeof(int32_t) + sizeof(uint8_t))) { + *ret = MSP_RESULT_ERROR; + break; + } + + const uint8_t datumFlag = sbufReadU8(src); + const int32_t targetAltitudeCm = (int32_t)sbufReadU32(src); + + float targetAltitudeLocalCm; + switch ((geoAltitudeDatumFlag_e)datumFlag) { + case NAV_WP_TAKEOFF_DATUM: + targetAltitudeLocalCm = (float)targetAltitudeCm; + break; + case NAV_WP_MSL_DATUM: + if (!posControl.gpsOrigin.valid) { + *ret = MSP_RESULT_ERROR; + break; + } + targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt); + break; + case NAV_WP_TERRAIN_DATUM: + default: + *ret = MSP_RESULT_ERROR; + break; + } + + if (*ret == MSP_RESULT_ERROR) { + break; + } + + updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET); + *ret = MSP_RESULT_ACK; + break; + } + #ifdef USE_SIMULATOR case MSP_SIMULATOR: tmp_u8 = sbufReadU8(src); // Get the Simulator MSP version diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index b44aa539887..251401fafcb 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -123,4 +123,6 @@ #define MSP2_INAV_GEOZONE_VERTEX 0x2212 #define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213 -#define MSP2_INAV_FULL_LOCAL_POSE 0x2220 \ No newline at end of file +#define MSP2_INAV_SET_ALT_TARGET 0x2215 + +#define MSP2_INAV_FULL_LOCAL_POSE 0x2220 diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index ddc7e23e76d..f5b2b8c82a3 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -729,7 +729,8 @@ typedef enum { typedef enum { NAV_WP_TAKEOFF_DATUM, - NAV_WP_MSL_DATUM + NAV_WP_MSL_DATUM, + NAV_WP_TERRAIN_DATUM } geoAltitudeDatumFlag_e; // geoSetOrigin stores the location provided in llh as a GPS origin in the From 94dcc3fed9d8fcd271eb3c2d1fe85f59aba3dcc1 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 11:31:18 -0500 Subject: [PATCH 2/8] add as logic condition --- docs/development/msp/msp_messages.json | 4 +++- src/main/fc/fc_msp.c | 26 +------------------------ src/main/navigation/navigation.c | 27 ++++++++++++++++++++++++++ src/main/navigation/navigation.h | 1 + src/main/programming/logic_condition.c | 4 ++++ src/main/programming/logic_condition.h | 1 + 6 files changed, 37 insertions(+), 26 deletions(-) diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index 7b79f69767a..94758d8f197 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10840,6 +10840,7 @@ "ctype": "uint8_t", "desc": "Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved)", "units": "", + "enum": "geoAltitudeDatumFlag_e", "optional": true }, { @@ -10857,7 +10858,8 @@ "name": "altitudeDatum", "ctype": "uint8_t", "desc": "Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM`", - "units": "" + "units": "", + "enum": "geoAltitudeDatumFlag_e" }, { "name": "altitudeTarget", diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 4e387bb3493..9f08d069104 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4114,12 +4114,6 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu case MSP2_INAV_SET_ALT_TARGET: { - const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); - if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) { - *ret = MSP_RESULT_ERROR; - break; - } - if (dataSize == 0) { sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM); sbufWriteU32(dst, (uint32_t)lrintf(posControl.desiredState.pos.z)); @@ -4135,29 +4129,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu const uint8_t datumFlag = sbufReadU8(src); const int32_t targetAltitudeCm = (int32_t)sbufReadU32(src); - float targetAltitudeLocalCm; - switch ((geoAltitudeDatumFlag_e)datumFlag) { - case NAV_WP_TAKEOFF_DATUM: - targetAltitudeLocalCm = (float)targetAltitudeCm; - break; - case NAV_WP_MSL_DATUM: - if (!posControl.gpsOrigin.valid) { - *ret = MSP_RESULT_ERROR; - break; - } - targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt); - break; - case NAV_WP_TERRAIN_DATUM: - default: + if (!navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)datumFlag, targetAltitudeCm)) { *ret = MSP_RESULT_ERROR; break; } - if (*ret == MSP_RESULT_ERROR) { - break; - } - - updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET); *ret = MSP_RESULT_ACK; break; } diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index e7f0774925e..a3752233149 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -5201,6 +5201,33 @@ bool navigationIsControllingAltitude(void) { return (stateFlags & NAV_CTL_ALT); } +bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm) +{ + const navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); + if (!(stateFlags & NAV_CTL_ALT) || (stateFlags & NAV_CTL_LAND) || navigationIsExecutingAnEmergencyLanding() || posControl.flags.estAltStatus == EST_NONE) { + return false; + } + + float targetAltitudeLocalCm; + switch (datumFlag) { + case NAV_WP_TAKEOFF_DATUM: + targetAltitudeLocalCm = (float)targetAltitudeCm; + break; + case NAV_WP_MSL_DATUM: + if (!posControl.gpsOrigin.valid) { + return false; + } + targetAltitudeLocalCm = (float)(targetAltitudeCm - posControl.gpsOrigin.alt); + break; + case NAV_WP_TERRAIN_DATUM: + default: + return false; + } + + updateClimbRateToAltitudeController(0.0f, targetAltitudeLocalCm, ROC_TO_ALT_TARGET); + return true; +} + bool navigationIsFlyingAutonomousMode(void) { navigationFSMStateFlags_t stateFlags = navGetCurrentStateFlags(); diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index f5b2b8c82a3..810fdc26ef8 100644 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -780,6 +780,7 @@ bool isFixedWingAutoThrottleManuallyIncreased(void); bool navigationIsFlyingAutonomousMode(void); bool navigationIsExecutingAnEmergencyLanding(void); bool navigationIsControllingAltitude(void); +bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm); /* Returns true if navConfig()->general.flags.rth_allow_landing is NAV_RTH_ALLOW_LANDING_ALWAYS * or if it's NAV_RTH_ALLOW_LANDING_FAILSAFE and failsafe mode is active. */ diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index edba68b8e94..fa1712e1f7f 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -471,6 +471,10 @@ static int logicConditionCompute( return true; break; + case LOGIC_CONDITION_SET_ALTITUDE_TARGET: + return navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)operandA, operandB); + break; + case LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE: if (operandA >= 0 && operandA <= 2) { diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 74ea96c98ee..e9d8eced5eb 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -86,6 +86,7 @@ typedef enum { LOGIC_CONDITION_RESET_MAG_CALIBRATION = 54, LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY = 55, LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED = 56, + LOGIC_CONDITION_SET_ALTITUDE_TARGET = 57, LOGIC_CONDITION_LAST } logicOperation_e; From 8f204761691afc77e938cedca3b8762008c87b20 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 12:40:10 -0500 Subject: [PATCH 3/8] updated msp docs --- docs/development/msp/inav_enums_ref.md | 11 +++++++---- docs/development/msp/msp_messages.checksum | 2 +- docs/development/msp/msp_ref.md | 21 ++++++++++++++++++++- docs/development/msp/rev | 2 +- 4 files changed, 29 insertions(+), 7 deletions(-) diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md index 9a4c64e6e39..b0941d90897 100644 --- a/docs/development/msp/inav_enums_ref.md +++ b/docs/development/msp/inav_enums_ref.md @@ -1385,7 +1385,7 @@ | `DEVHW_MS4525` | 49 | | | `DEVHW_DLVR` | 50 | | | `DEVHW_M25P16` | 51 | | -| `DEVHW_W25N01G` | 52 | | +| `DEVHW_W25N` | 52 | | | `DEVHW_UG2864` | 53 | | | `DEVHW_SDCARD` | 54 | | | `DEVHW_IRLOCK` | 55 | | @@ -1994,6 +1994,7 @@ |---|---:|---| | `NAV_WP_TAKEOFF_DATUM` | 0 | | | `NAV_WP_MSL_DATUM` | 1 | | +| `NAV_WP_TERRAIN_DATUM` | 2 | | --- ## `geoOriginResetMode_e` @@ -2843,6 +2844,7 @@ | `LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED` | 46 | | | `LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED` | 47 | | | `LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION` | 48 | | +| `LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET` | 49 | | --- ## `logicOperation_e` @@ -2908,7 +2910,8 @@ | `LOGIC_CONDITION_RESET_MAG_CALIBRATION` | 54 | | | `LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY` | 55 | | | `LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED` | 56 | | -| `LOGIC_CONDITION_LAST` | 57 | | +| `LOGIC_CONDITION_SET_ALTITUDE_TARGET` | 57 | | +| `LOGIC_CONDITION_LAST` | 58 | | --- ## `logicWaypointOperands_e` @@ -4740,7 +4743,7 @@ --- ## `sdcardReceiveBlockStatus_e` -> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c +> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c | Enumerator | Value | Condition | |---|---:|---| @@ -4751,7 +4754,7 @@ --- ## `sdcardReceiveBlockStatus_e` -> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c +> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c | Enumerator | Value | Condition | |---|---:|---| diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index 3c235d8aaf9..76a646c0358 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -ca27e198f4405b721ad8a15719e15e5d +b1b9c4b89d7285401e4d7d22ca0da717 diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md index 97851bcec1f..0e837c0fae9 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/msp_ref.md @@ -10,7 +10,8 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i For current generation code, see [documentation project](https://github.com/xznhj8129/msp_documentation) (temporary until official implementation) -**JSON file rev: 2** +**JSON file rev: 3 +** **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** @@ -411,6 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh [8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone) [8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex) [8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex) +[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target) [8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose) [12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind) @@ -4492,6 +4494,23 @@ For current generation code, see [documentation project](https://github.com/xznh **Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude). +## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)` +**Description:** Get or set the active altitude hold target. + +**Request Payload:** +|Field|C Type|Size (Bytes)|Units|Description| +|---|---|---|---|---| +| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved) | +| `altitudeTarget` | `int32_t` | 4 | cm | Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above | + +**Reply Payload:** +|Field|C Type|Size (Bytes)|Units|Description| +|---|---|---|---|---| +| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM` | +| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) | + +**Notes:** Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected). + ## `MSP2_INAV_FULL_LOCAL_POSE (8736 / 0x2220)` **Description:** Provides estimates of current attitude, local NEU position, and velocity. diff --git a/docs/development/msp/rev b/docs/development/msp/rev index d8263ee9860..00750edc07d 100644 --- a/docs/development/msp/rev +++ b/docs/development/msp/rev @@ -1 +1 @@ -2 \ No newline at end of file +3 From f2aa78009f7752936c04fa791b791bb1d3e4ce05 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 14:04:19 -0500 Subject: [PATCH 4/8] add mavlink command --- docs/development/msp/msp_messages.checksum | 2 +- docs/development/msp/msp_messages.json | 76 +++++++++++++--------- docs/development/msp/msp_ref.md | 26 ++++++-- docs/development/msp/original_msp_ref.md | 1 - src/main/fc/fc_msp.c | 2 + src/main/telemetry/mavlink.c | 51 +++++++++++++-- 6 files changed, 111 insertions(+), 47 deletions(-) diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index 76a646c0358..13116c1d9ef 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -b1b9c4b89d7285401e4d7d22ca0da717 +590fbe3daaa6de1cef98b521f9cf8ede diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index 94758d8f197..7a3d22f87e2 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10833,44 +10833,56 @@ "code": 8725, "mspv": 2, "variable_len": true, - "request": { - "payload": [ - { - "name": "altitudeDatum", - "ctype": "uint8_t", - "desc": "Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved)", - "units": "", - "enum": "geoAltitudeDatumFlag_e", - "optional": true + "variants": { + "get": { + "description": "Get current altitude target", + "request": { + "payload": null }, - { - "name": "altitudeTarget", - "ctype": "int32_t", - "desc": "Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above", - "units": "cm", - "optional": true + "reply": { + "payload": [ + { + "name": "altitudeDatum", + "ctype": "uint8_t", + "desc": "Default internal reference altitude datum `NAV_WP_TAKEOFF_DATUM`", + "units": "", + "enum": "geoAltitudeDatumFlag_e" + }, + { + "name": "altitudeTarget", + "ctype": "int32_t", + "desc": "Current altitude target (`posControl.desiredState.pos.z`)", + "units": "cm" + } + ] } - ] - }, - "reply": { - "payload": [ - { - "name": "altitudeDatum", - "ctype": "uint8_t", - "desc": "Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM`", - "units": "", - "enum": "geoAltitudeDatumFlag_e" + }, + "set": { + "description": "Set new altitude target", + "request": { + "payload": [ + { + "name": "altitudeDatum", + "ctype": "uint8_t", + "desc": "Altitude reference datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (not implemented yet)", + "units": "", + "enum": "geoAltitudeDatumFlag_e" + }, + { + "name": "altitudeTarget", + "ctype": "int32_t", + "desc": "Desired altitude target according to reference datum", + "units": "cm" + } + ] }, - { - "name": "altitudeTarget", - "ctype": "int32_t", - "desc": "Current altitude target (`posControl.desiredState.pos.z`)", - "units": "cm" + "reply": { + "payload": null } - ] + } }, "notes": "Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected).", - "description": "Get or set the active altitude hold target." + "description": "Get or set the active altitude hold target using updateClimbRateToAltitudeController." }, "MSP2_INAV_FULL_LOCAL_POSE": { "code": 8736, diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md index 0e837c0fae9..b51d72d0473 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/msp_ref.md @@ -4495,19 +4495,31 @@ For current generation code, see [documentation project](https://github.com/xznh **Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude). ## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)` -**Description:** Get or set the active altitude hold target. +**Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController. +#### Variant: `get` + +**Description:** Get current altitude target + +**Request Payload:** **None** -**Request Payload:** +**Reply Payload:** |Field|C Type|Size (Bytes)|Units|Description| |---|---|---|---|---| -| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (reserved) | -| `altitudeTarget` | `int32_t` | 4 | cm | Desired altitude target (`updateClimbRateToAltitudeController(…, ROC_TO_ALT_TARGET)`), datum as above | +| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Default internal reference altitude datum `NAV_WP_TAKEOFF_DATUM` | +| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) | + +#### Variant: `set` + +**Description:** Set new altitude target -**Reply Payload:** +**Request Payload:** |Field|C Type|Size (Bytes)|Units|Description| |---|---|---|---|---| -| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Datum flag returned (`geoAltitudeDatumFlag_e`), currently `NAV_WP_TAKEOFF_DATUM` | -| `altitudeTarget` | `int32_t` | 4 | cm | Current altitude target (`posControl.desiredState.pos.z`) | +| `altitudeDatum` | `uint8_t` | 1 | [geoAltitudeDatumFlag_e](https://github.com/iNavFlight/inav/wiki/Enums-reference#enum-geoaltitudedatumflag_e) | Altitude reference datum flag (`geoAltitudeDatumFlag_e`): `NAV_WP_TAKEOFF_DATUM`, `NAV_WP_MSL_DATUM`, `NAV_WP_TERRAIN_DATUM` (not implemented yet) | +| `altitudeTarget` | `int32_t` | 4 | cm | Desired altitude target according to reference datum | + +**Reply Payload:** **None** + **Notes:** Empty request payload returns the current altitude target with datum. Sending a 5-byte payload sets a new target: 1 byte datum, 4 bytes altitude. Command is rejected unless altitude control is active, not landing/emergency landing, altitude estimation is valid, and datum is supported (MSL requires valid GPS origin; TERRAIN is reserved and rejected). diff --git a/docs/development/msp/original_msp_ref.md b/docs/development/msp/original_msp_ref.md index d635bbc6843..209ca629481 100644 --- a/docs/development/msp/original_msp_ref.md +++ b/docs/development/msp/original_msp_ref.md @@ -2,7 +2,6 @@ # WARNING: DEPRECATED, OBSOLETE, FULL OF ERRORS, DO NOT USE AS REFERENCE!!! # (OBSOLETE) INAV MSP Messages reference -**Warning: Work in progress**\ **Generated with Gemini 2.5 Pro Preview O3-25 on source code files**\ **Verification needed, exercise caution until completely verified for accuracy and cleared**\ **Refer to source for absolute certainty** diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 9f08d069104..1597b8f88b7 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4112,6 +4112,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu break; #endif +#ifdef USE_BARO case MSP2_INAV_SET_ALT_TARGET: { if (dataSize == 0) { @@ -4137,6 +4138,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu *ret = MSP_RESULT_ACK; break; } +#endif #ifdef USE_SIMULATOR case MSP_SIMULATOR: diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index d5084b32a62..717039aba12 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -1157,7 +1157,6 @@ static bool handleIncoming_MISSION_REQUEST(void) return false; } - static bool handleIncoming_COMMAND_INT(void) { mavlink_command_int_t msg; @@ -1226,6 +1225,51 @@ static bool handleIncoming_COMMAND_INT(void) mavlinkSendMessage(); } return true; +#ifdef USE_BARO + } else if (msg.command == MAV_CMD_DO_CHANGE_ALTITUDE) { + const float altitudeMeters = msg.param1; + const uint8_t frame = (uint8_t)msg.frame; + + geoAltitudeDatumFlag_e datum; + switch (frame) { + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_INT: + datum = NAV_WP_MSL_DATUM; + break; + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: + case MAV_FRAME_LOCAL_NED: + case MAV_FRAME_LOCAL_OFFSET_NED: + case MAV_FRAME_BODY_NED: + case MAV_FRAME_BODY_FRD: + datum = NAV_WP_TAKEOFF_DATUM; + break; + case MAV_FRAME_GLOBAL_TERRAIN_ALT: + case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: + default: + mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, + msg.command, + MAV_RESULT_UNSUPPORTED, + 0, + 0, + mavRecvMsg.sysid, + mavRecvMsg.compid); + mavlinkSendMessage(); + return true; + } + + const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f); + const bool accepted = navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm); + mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, + msg.command, + accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED, + 0, + 0, + mavRecvMsg.sysid, + mavRecvMsg.compid); + mavlinkSendMessage(); + return true; +#endif } return false; } @@ -1351,11 +1395,6 @@ static bool processMAVLinkIncomingTelemetry(void) return handleIncoming_MISSION_ITEM(); case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: return handleIncoming_MISSION_REQUEST_LIST(); - - //TODO: - //case MAVLINK_MSG_ID_COMMAND_LONG; //up to 7 float parameters - //return handleIncoming_COMMAND_LONG(); - case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers return handleIncoming_COMMAND_INT(); case MAVLINK_MSG_ID_MISSION_REQUEST: From 4d61538b9a7467805f665833530afbd0abfbd7f8 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 14:08:01 -0500 Subject: [PATCH 5/8] narrow mavlink frames --- src/main/telemetry/mavlink.c | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 717039aba12..13e6c0344b7 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -1238,14 +1238,8 @@ static bool handleIncoming_COMMAND_INT(void) break; case MAV_FRAME_GLOBAL_RELATIVE_ALT: case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: - case MAV_FRAME_LOCAL_NED: - case MAV_FRAME_LOCAL_OFFSET_NED: - case MAV_FRAME_BODY_NED: - case MAV_FRAME_BODY_FRD: datum = NAV_WP_TAKEOFF_DATUM; break; - case MAV_FRAME_GLOBAL_TERRAIN_ALT: - case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: default: mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, msg.command, @@ -1395,6 +1389,11 @@ static bool processMAVLinkIncomingTelemetry(void) return handleIncoming_MISSION_ITEM(); case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: return handleIncoming_MISSION_REQUEST_LIST(); + + //TODO: + //case MAVLINK_MSG_ID_COMMAND_LONG; //up to 7 float parameters + //return handleIncoming_COMMAND_LONG(); + case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers return handleIncoming_COMMAND_INT(); case MAVLINK_MSG_ID_MISSION_REQUEST: From eec54810e3ad0b8e150cae457a86d307fe69a323 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 14:10:53 -0500 Subject: [PATCH 6/8] change msp msg name --- docs/development/msp/msp_messages.checksum | 2 +- docs/development/msp/msp_messages.json | 2 +- docs/development/msp/msp_ref.md | 4 ++-- src/main/fc/fc_msp.c | 2 +- src/main/msp/msp_protocol_v2_inav.h | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index 13116c1d9ef..d6c6f3d080f 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -590fbe3daaa6de1cef98b521f9cf8ede +d03d2a93006b50de49043e9da6d7403a diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index 7a3d22f87e2..a4d98d2cd48 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10829,7 +10829,7 @@ "notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).", "description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone." }, - "MSP2_INAV_SET_ALT_TARGET": { + "MSP2_INAV_SET_TARGET": { "code": 8725, "mspv": 2, "variable_len": true, diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md index b51d72d0473..c4ffe82882e 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/msp_ref.md @@ -412,7 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh [8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone) [8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex) [8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex) -[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target) +[8725 - MSP2_INAV_SET_TARGET](#msp2_inav_set_target) [8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose) [12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind) @@ -4494,7 +4494,7 @@ For current generation code, see [documentation project](https://github.com/xznh **Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude). -## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)` +## `MSP2_INAV_SET_TARGET (8725 / 0x2215)` **Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController. #### Variant: `get` diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 1597b8f88b7..5ee51d80f30 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4113,7 +4113,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu #endif #ifdef USE_BARO - case MSP2_INAV_SET_ALT_TARGET: + case MSP2_INAV_SET_TARGET: { if (dataSize == 0) { sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM); diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 251401fafcb..7d4387bdfbf 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -123,6 +123,6 @@ #define MSP2_INAV_GEOZONE_VERTEX 0x2212 #define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213 -#define MSP2_INAV_SET_ALT_TARGET 0x2215 +#define MSP2_INAV_SET_TARGET 0x2215 #define MSP2_INAV_FULL_LOCAL_POSE 0x2220 From 125efbbd40b9000df17f02ba118e6e8ce8148a1d Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 14:12:29 -0500 Subject: [PATCH 7/8] Revert "change msp msg name" This reverts commit eec54810e3ad0b8e150cae457a86d307fe69a323. --- docs/development/msp/msp_messages.checksum | 2 +- docs/development/msp/msp_messages.json | 2 +- docs/development/msp/msp_ref.md | 4 ++-- src/main/fc/fc_msp.c | 2 +- src/main/msp/msp_protocol_v2_inav.h | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index d6c6f3d080f..13116c1d9ef 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -d03d2a93006b50de49043e9da6d7403a +590fbe3daaa6de1cef98b521f9cf8ede diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index a4d98d2cd48..7a3d22f87e2 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10829,7 +10829,7 @@ "notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).", "description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone." }, - "MSP2_INAV_SET_TARGET": { + "MSP2_INAV_SET_ALT_TARGET": { "code": 8725, "mspv": 2, "variable_len": true, diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md index c4ffe82882e..b51d72d0473 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/msp_ref.md @@ -412,7 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh [8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone) [8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex) [8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex) -[8725 - MSP2_INAV_SET_TARGET](#msp2_inav_set_target) +[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target) [8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose) [12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind) @@ -4494,7 +4494,7 @@ For current generation code, see [documentation project](https://github.com/xznh **Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude). -## `MSP2_INAV_SET_TARGET (8725 / 0x2215)` +## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)` **Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController. #### Variant: `get` diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 5ee51d80f30..1597b8f88b7 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4113,7 +4113,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu #endif #ifdef USE_BARO - case MSP2_INAV_SET_TARGET: + case MSP2_INAV_SET_ALT_TARGET: { if (dataSize == 0) { sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM); diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 7d4387bdfbf..251401fafcb 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -123,6 +123,6 @@ #define MSP2_INAV_GEOZONE_VERTEX 0x2212 #define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213 -#define MSP2_INAV_SET_TARGET 0x2215 +#define MSP2_INAV_SET_ALT_TARGET 0x2215 #define MSP2_INAV_FULL_LOCAL_POSE 0x2220 From 849bcad5205306b147b1ec994be71e07a60bed10 Mon Sep 17 00:00:00 2001 From: frogmane <7685285+xznhj8129@users.noreply.github.com> Date: Sat, 29 Nov 2025 14:14:05 -0500 Subject: [PATCH 8/8] change msp msg name --- docs/development/msp/msp_messages.checksum | 2 +- docs/development/msp/msp_messages.json | 2 +- docs/development/msp/msp_ref.md | 4 ++-- src/main/fc/fc_msp.c | 2 +- src/main/msp/msp_protocol_v2_inav.h | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum index 13116c1d9ef..f90eaa7b1bf 100644 --- a/docs/development/msp/msp_messages.checksum +++ b/docs/development/msp/msp_messages.checksum @@ -1 +1 @@ -590fbe3daaa6de1cef98b521f9cf8ede +7601652331e47d41941de8efdcb0c1e7 diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index 7a3d22f87e2..3710e411153 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -10829,7 +10829,7 @@ "notes": "Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude).", "description": "Sets a specific vertex (or center+radius for circular zones) for a Geozone." }, - "MSP2_INAV_SET_ALT_TARGET": { + "MSP2_INAV_ALT_TARGET": { "code": 8725, "mspv": 2, "variable_len": true, diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/msp_ref.md index b51d72d0473..ba1e32ac9a2 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/msp_ref.md @@ -412,7 +412,7 @@ For current generation code, see [documentation project](https://github.com/xznh [8721 - MSP2_INAV_SET_GEOZONE](#msp2_inav_set_geozone) [8722 - MSP2_INAV_GEOZONE_VERTEX](#msp2_inav_geozone_vertex) [8723 - MSP2_INAV_SET_GEOZONE_VERTEX](#msp2_inav_set_geozone_vertex) -[8725 - MSP2_INAV_SET_ALT_TARGET](#msp2_inav_set_alt_target) +[8725 - MSP2_INAV_ALT_TARGET](#msp2_inav_alt_target) [8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose) [12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind) @@ -4494,7 +4494,7 @@ For current generation code, see [documentation project](https://github.com/xznh **Notes:** Requires `USE_GEOZONE`. Expects 10 bytes (Polygon) or 14 bytes (Circular). Returns error if indexes invalid or if trying to set vertex beyond `vertexCount` defined in `MSP2_INAV_SET_GEOZONE`. Calls `geozoneSetVertex()`. For circular zones, sets center (vertex 0) and radius (vertex 1's latitude). -## `MSP2_INAV_SET_ALT_TARGET (8725 / 0x2215)` +## `MSP2_INAV_ALT_TARGET (8725 / 0x2215)` **Description:** Get or set the active altitude hold target using updateClimbRateToAltitudeController. #### Variant: `get` diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 1597b8f88b7..5ed2f29d067 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -4113,7 +4113,7 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu #endif #ifdef USE_BARO - case MSP2_INAV_SET_ALT_TARGET: + case MSP2_INAV_ALT_TARGET: { if (dataSize == 0) { sbufWriteU8(dst, NAV_WP_TAKEOFF_DATUM); diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 251401fafcb..217409f8422 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -123,6 +123,6 @@ #define MSP2_INAV_GEOZONE_VERTEX 0x2212 #define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213 -#define MSP2_INAV_SET_ALT_TARGET 0x2215 +#define MSP2_INAV_ALT_TARGET 0x2215 #define MSP2_INAV_FULL_LOCAL_POSE 0x2220