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
4 changes: 2 additions & 2 deletions docs/LedStrip.md
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ Enable the Led Strip feature via the GUI under setup.
Configure the leds from the Led Strip tab in the INAV GUI.
First setup how the led's are laid out so that you can visualize it later as you configure and so the flight controller knows how many led's there are available.

There is a step by step guide on how to use the GUI to configure the Led Strip feature using the GUI http://blog.oscarliang.net/setup-rgb-led-cleanflight/ which was published early 2015 by Oscar Liang which may or may not be up-to-date by the time you read this.
There is a step by step guide on how to use the GUI to configure the Led Strip feature using the GUI https://oscarliang.com/setup-led-betaflight/ which was published early 2015 by Oscar Liang which may or may not be up-to-date by the time you read this.

CLI:
Enable the `LED_STRIP` feature via the cli:
Expand Down Expand Up @@ -605,4 +605,4 @@ This also means that you can make sure that each R,G and B LED in each LED modul

After a short delay the LEDs will show the unarmed color sequence and or low-battery warning sequence.

Also check that the feature `LED_STRIP` was correctly enabled and that it does not conflict with other features, as above.
Also check that the feature `LED_STRIP` was correctly enabled and that it does not conflict with other features, as above.
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
Loading