Skip to content
Merged
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
7 changes: 4 additions & 3 deletions docs/development/msp/inav_enums_ref.md
Original file line number Diff line number Diff line change
Expand Up @@ -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 | |
Expand Down Expand Up @@ -2843,6 +2843,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 | |

---
## <a id="enum-logicoperation_e"></a>`logicOperation_e`
Expand Down Expand Up @@ -4740,7 +4741,7 @@
---
## <a id="enum-sdcardreceiveblockstatus_e"></a>`sdcardReceiveBlockStatus_e`

> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c
> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c

| Enumerator | Value | Condition |
|---|---:|---|
Expand All @@ -4751,7 +4752,7 @@
---
## <a id="enum-sdcardreceiveblockstatus_e"></a>`sdcardReceiveBlockStatus_e`

> Source: ../../../src/main/drivers/sdcard/sdcard_sdio.c
> Source: ../../../src/main/drivers/sdcard/sdcard_spi.c

| Enumerator | Value | Condition |
|---|---:|---|
Expand Down
2 changes: 1 addition & 1 deletion docs/development/msp/msp_messages.checksum
Original file line number Diff line number Diff line change
@@ -1 +1 @@
ca27e198f4405b721ad8a15719e15e5d
7db80f38dda2265704e7852630a02a83
23 changes: 23 additions & 0 deletions docs/development/msp/msp_messages.json
Original file line number Diff line number Diff line change
Expand Up @@ -10829,6 +10829,29 @@
"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_GVAR": {
"code": 8724,
"mspv": 2,
"request": {
"payload": [
{
"name": "gvarIndex",
"ctype": "uint8_t",
"desc": "Index of the Global Variable to set",
"units": "Index"
},
{
"name": "value",
"ctype": "int32_t",
"desc": "New value to store (clamped to configured min/max by `gvSet()`)",
"units": ""
}
]
},
"reply": null,
"notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`.",
"description": "Sets the specified Global Variable (GVAR) to the provided value."
},
"MSP2_INAV_FULL_LOCAL_POSE": {
"code": 8736,
"mspv": 2,
Expand Down
17 changes: 16 additions & 1 deletion docs/development/msp/msp_ref.md
Original file line number Diff line number Diff line change
Expand Up @@ -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**

Expand Down Expand Up @@ -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)
[8724 - MSP2_INAV_SET_GVAR](#msp2_inav_set_gvar)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)

Expand Down Expand Up @@ -4492,6 +4494,19 @@ 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).

## <a id="msp2_inav_set_gvar"></a>`MSP2_INAV_SET_GVAR (8724 / 0x2214)`
**Description:** Sets the specified Global Variable (GVAR) to the provided value.

**Request Payload:**
|Field|C Type|Size (Bytes)|Units|Description|
|---|---|---|---|---|
| `gvarIndex` | `uint8_t` | 1 | Index | Index of the Global Variable to set |
| `value` | `int32_t` | 4 | - | New value to store (clamped to configured min/max by `gvSet()`) |

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

**Notes:** Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 5 bytes. Returns error if index is outside `MAX_GLOBAL_VARIABLES`.

## <a id="msp2_inav_full_local_pose"></a>`MSP2_INAV_FULL_LOCAL_POSE (8736 / 0x2220)`
**Description:** Provides estimates of current attitude, local NEU position, and velocity.

Expand Down
2 changes: 1 addition & 1 deletion docs/development/msp/rev
Original file line number Diff line number Diff line change
@@ -1 +1 @@
2
3
17 changes: 17 additions & 0 deletions src/main/fc/fc_msp.c
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

High-level Suggestion

Add a safety check to prevent the MSP2_INAV_SET_GVAR command from executing if the aircraft is armed. This avoids unintended flight behavior changes caused by modifying Global Variables mid-flight. [High-level, importance: 9]

Solution Walkthrough:

Before:

case MSP2_INAV_SET_GVAR:
    if (dataSize != 5) {
        return MSP_RESULT_ERROR;
    }
    {
        uint8_t gvarIndex;
        if (!sbufReadU8Safe(&gvarIndex, src)) {
            return MSP_RESULT_ERROR;
        }
        const int32_t gvarValue = (int32_t)sbufReadU32(src);
        if (gvarIndex >= MAX_GLOBAL_VARIABLES) {
            return MSP_RESULT_ERROR;
        }
        gvSet(gvarIndex, gvarValue);
    }
    break;

After:

case MSP2_INAV_SET_GVAR:
    if (ARMING_FLAG(ARMED)) {
        return MSP_RESULT_ERROR;
    }
    if (dataSize != 5) {
        return MSP_RESULT_ERROR;
    }
    {
        uint8_t gvarIndex;
        if (!sbufReadU8Safe(&gvarIndex, src)) {
            return MSP_RESULT_ERROR;
        }
        const int32_t gvarValue = (int32_t)sbufReadU32(src);
        if (gvarIndex >= MAX_GLOBAL_VARIABLES) {
            return MSP_RESULT_ERROR;
        }
        gvSet(gvarIndex, gvarValue);
    }
    break;

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That would defeat the point

Original file line number Diff line number Diff line change
Expand Up @@ -2340,6 +2340,23 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
} else
return MSP_RESULT_ERROR;
break;

case MSP2_INAV_SET_GVAR:
if (dataSize != 5) {
return MSP_RESULT_ERROR;
}
{
uint8_t gvarIndex;
if (!sbufReadU8Safe(&gvarIndex, src)) {
return MSP_RESULT_ERROR;
}
const int32_t gvarValue = (int32_t)sbufReadU32(src);
if (gvarIndex >= MAX_GLOBAL_VARIABLES) {
return MSP_RESULT_ERROR;
}
gvSet(gvarIndex, gvarValue);
}
break;
#endif
case MSP2_COMMON_SET_MOTOR_MIXER:
sbufReadU8Safe(&tmp_u8, src);
Expand Down
3 changes: 2 additions & 1 deletion src/main/msp/msp_protocol_v2_inav.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,5 +122,6 @@
#define MSP2_INAV_SET_GEOZONE 0x2211
#define MSP2_INAV_GEOZONE_VERTEX 0x2212
#define MSP2_INAV_SET_GEOZONE_VERTEX 0x2213
#define MSP2_INAV_SET_GVAR 0x2214

#define MSP2_INAV_FULL_LOCAL_POSE 0x2220
#define MSP2_INAV_FULL_LOCAL_POSE 0x2220