diff --git a/.github/scripts/check-pg-versions.sh b/.github/scripts/check-pg-versions.sh new file mode 100755 index 00000000000..f5ec2895dd1 --- /dev/null +++ b/.github/scripts/check-pg-versions.sh @@ -0,0 +1,169 @@ +#!/bin/bash +# +# Check if parameter group struct modifications include version increments +# This prevents settings corruption when struct layout changes without version bump +# +# Exit codes: +# 0 - No issues found +# 1 - Potential issues detected (will post comment) +# 2 - Script error + +set -euo pipefail + +# Output file for issues found +ISSUES_FILE=$(mktemp) +trap "rm -f $ISSUES_FILE" EXIT + +# Color output for local testing +if [ -t 1 ]; then + RED='\033[0;31m' + GREEN='\033[0;32m' + YELLOW='\033[1;33m' + NC='\033[0m' # No Color +else + RED='' + GREEN='' + YELLOW='' + NC='' +fi + +echo "πŸ” Checking for Parameter Group version updates..." + +# Get base and head commits +BASE_REF=${GITHUB_BASE_REF:-} +HEAD_REF=${GITHUB_HEAD_REF:-} + +if [ -z "$BASE_REF" ] || [ -z "$HEAD_REF" ]; then + echo "⚠️ Warning: Not running in GitHub Actions PR context" + echo "Using git diff against HEAD~1 for local testing" + BASE_COMMIT="HEAD~1" + HEAD_COMMIT="HEAD" +else + BASE_COMMIT="origin/$BASE_REF" + HEAD_COMMIT="HEAD" +fi + +# Get list of changed files +CHANGED_FILES=$(git diff --name-only $BASE_COMMIT..$HEAD_COMMIT | grep -E '\.(c|h)$' || true) + +if [ -z "$CHANGED_FILES" ]; then + echo "βœ… No C/H files changed" + exit 0 +fi + +echo "πŸ“ Changed files:" +echo "$CHANGED_FILES" | sed 's/^/ /' + +# Function to extract PG info from a file +check_file_for_pg_changes() { + local file=$1 + local diff_output=$(git diff $BASE_COMMIT..$HEAD_COMMIT -- "$file") + + # Check if file contains PG_REGISTER (in either old or new version) + if ! echo "$diff_output" | grep -q "PG_REGISTER"; then + return 0 + fi + + echo " πŸ”Ž Checking $file (contains PG_REGISTER)" + + # Extract all PG_REGISTER lines from the diff (both old and new) + local pg_registers=$(echo "$diff_output" | grep -E "^[-+].*PG_REGISTER" || true) + + if [ -z "$pg_registers" ]; then + # PG_REGISTER exists but wasn't changed + # Still need to check if the struct changed + pg_registers=$(git show $HEAD_COMMIT:"$file" | grep "PG_REGISTER" || true) + fi + + # Process each PG registration + while IFS= read -r pg_line; do + [ -z "$pg_line" ] && continue + + # Extract struct name and version + # Pattern: PG_REGISTER.*\((\w+),\s*(\w+),\s*PG_\w+,\s*(\d+)\) + if [[ $pg_line =~ PG_REGISTER[^(]*\(([^,]+),([^,]+),([^,]+),([^)]+)\) ]]; then + local struct_type="${BASH_REMATCH[1]}" + local pg_name="${BASH_REMATCH[2]}" + local pg_id="${BASH_REMATCH[3]}" + local version="${BASH_REMATCH[4]}" + + # Clean up whitespace + struct_type=$(echo "$struct_type" | xargs) + version=$(echo "$version" | xargs) + + echo " πŸ“‹ Found: $struct_type (version $version)" + + # Check if this struct's typedef was modified + local struct_pattern="typedef struct ${struct_type%_t}_s" + # Isolate struct body from diff, remove comments and empty lines, then check for remaining changes + local struct_body_diff=$(echo "$diff_output" | sed -n "/${struct_pattern}/,/\}.*${struct_type};/p") + local struct_changes=$(echo "$struct_body_diff" | grep -E "^[-+]" \ + | grep -v -E "^[-+]\s*(typedef struct|}|//|\*)" \ + | sed -E 's://.*$::' \ + | sed -E 's:/\*.*\*/::' \ + | tr -d '[:space:]') + + if [ -n "$struct_changes" ]; then + echo " ⚠️ Struct definition modified" + + # Check if version was incremented in this diff + local old_version=$(echo "$diff_output" | grep "^-.*PG_REGISTER.*$struct_type" | grep -oP ',\s*\K\d+(?=\s*\))' || echo "") + local new_version=$(echo "$diff_output" | grep "^+.*PG_REGISTER.*$struct_type" | grep -oP ',\s*\K\d+(?=\s*\))' || echo "") + + if [ -n "$old_version" ] && [ -n "$new_version" ]; then + if [ "$new_version" -le "$old_version" ]; then + echo " ❌ Version NOT incremented ($old_version β†’ $new_version)" + + # Find line number of PG_REGISTER + local line_num=$(git show $HEAD_COMMIT:"$file" | grep -n "PG_REGISTER.*$struct_type" | cut -d: -f1 | head -1) + + # Add to issues list + cat >> $ISSUES_FILE << EOF +### \`$struct_type\` ($file:$line_num) +- **Struct modified:** Field changes detected +- **Version status:** ❌ Not incremented (version $version) +- **Recommendation:** Review changes and increment version if needed + +EOF + else + echo " βœ… Version incremented ($old_version β†’ $new_version)" + fi + elif [ -z "$old_version" ] || [ -z "$new_version" ]; then + # Couldn't determine version change, but struct was modified + echo " ⚠️ Could not determine if version was incremented" + + local line_num=$(git show $HEAD_COMMIT:"$file" | grep -n "PG_REGISTER.*$struct_type" | cut -d: -f1 | head -1) + + cat >> $ISSUES_FILE << EOF +### \`$struct_type\` ($file:$line_num) +- **Struct modified:** Field changes detected +- **Version status:** ⚠️ Unable to verify version increment +- **Current version:** $version +- **Recommendation:** Verify version was incremented if struct layout changed + +EOF + fi + else + echo " βœ… Struct unchanged" + fi + fi + done <<< "$pg_registers" +} + +# Check each changed file +while IFS= read -r file; do + check_file_for_pg_changes "$file" +done <<< "$CHANGED_FILES" + +# Check if any issues were found +if [ -s $ISSUES_FILE ]; then + echo "" + echo "${YELLOW}⚠️ Potential PG version issues detected${NC}" + echo "Output saved to: $ISSUES_FILE" + cat $ISSUES_FILE + exit 1 +else + echo "" + echo "${GREEN}βœ… No PG version issues detected${NC}" + exit 0 +fi diff --git a/.github/workflows/README.md b/.github/workflows/README.md new file mode 100644 index 00000000000..967080a66fb --- /dev/null +++ b/.github/workflows/README.md @@ -0,0 +1,127 @@ +# GitHub Actions Workflows + +This directory contains automated CI/CD workflows for the INAV project. + +## Active Workflows + +### Build and Test + +#### `ci.yml` - Build Firmware +**Triggers:** Pull requests, pushes to maintenance branches +**Purpose:** Compiles INAV firmware for all targets to verify builds succeed +**Matrix:** 15 parallel build jobs for faster CI + +#### `nightly-build.yml` - Nightly Builds +**Triggers:** Scheduled nightly +**Purpose:** Creates nightly development builds for testing + +### Documentation + +#### `docs.yml` - Documentation Build +**Triggers:** Pull requests affecting documentation +**Purpose:** Validates documentation builds correctly + +### Code Quality + +#### `pg-version-check.yml` - Parameter Group Version Check +**Triggers:** Pull requests to maintenance-9.x and maintenance-10.x +**Purpose:** Detects parameter group struct modifications and verifies version increments +**Why:** Prevents settings corruption when struct layout changes without version bump + +**How it works:** +1. Scans changed .c/.h files for `PG_REGISTER` entries +2. Detects if associated struct typedefs were modified +3. Checks if the PG version parameter was incremented +4. Posts helpful comment if version not incremented + +**Reference:** See `docs/development/parameter_groups/` for PG system documentation + +**Script:** `.github/scripts/check-pg-versions.sh` + +**When to increment PG versions:** +- βœ… Adding/removing fields from struct +- βœ… Changing field types or sizes +- βœ… Reordering fields +- βœ… Adding/removing packing attributes +- ❌ Only changing `PG_RESET_TEMPLATE` default values +- ❌ Only changing comments + +### Pull Request Helpers + +#### `pr-branch-suggestion.yml` - Branch Targeting Suggestion +**Triggers:** PRs targeting master branch +**Purpose:** Suggests using maintenance-9.x or maintenance-10.x instead + +#### `non-code-change.yaml` - Non-Code Change Detection +**Triggers:** Pull requests +**Purpose:** Detects PRs with only documentation/formatting changes + +## Configuration Files + +- `../.github/stale.yml` - Stale issue/PR management +- `../.github/no-response.yml` - Auto-close issues without response +- `../.github/issue_label_bot.yaml` - Automatic issue labeling + +## Adding New Workflows + +When adding workflows: + +1. **Use descriptive names** - Make purpose clear from filename +2. **Document in this README** - Add entry above with purpose and triggers +3. **Set appropriate permissions** - Principle of least privilege +4. **Test in fork first** - Verify before submitting to main repo +5. **Handle errors gracefully** - Don't block CI unnecessarily + +### Common Patterns + +**Checkout with history:** +```yaml +- uses: actions/checkout@v4 + with: + fetch-depth: 0 +``` + +**Post PR comments:** +```yaml +- uses: actions/github-script@v7 + with: + script: | + await github.rest.issues.createComment({ + owner: context.repo.owner, + repo: context.repo.repo, + issue_number: context.issue.number, + body: 'Comment text' + }); +``` + +**Run bash scripts:** +```yaml +- run: bash .github/scripts/script-name.sh + env: + GITHUB_BASE_REF: ${{ github.base_ref }} +``` + +## Permissions + +Workflows use GitHub's fine-grained permissions: + +- `contents: read` - Read repository code +- `pull-requests: write` - Post/update PR comments +- `actions: read` - Read workflow run data + +## Local Testing + +Scripts in `.github/scripts/` can be run locally: + +```bash +cd inav +export GITHUB_BASE_REF=maintenance-9.x +export GITHUB_HEAD_REF=feature-branch +bash .github/scripts/check-pg-versions.sh +``` + +## References + +- [GitHub Actions Documentation](https://docs.github.com/en/actions) +- [Workflow Syntax](https://docs.github.com/en/actions/reference/workflow-syntax-for-github-actions) +- [GitHub Script Action](https://github.com/actions/github-script) diff --git a/.github/workflows/pg-version-check.yml b/.github/workflows/pg-version-check.yml new file mode 100644 index 00000000000..d9d8c289930 --- /dev/null +++ b/.github/workflows/pg-version-check.yml @@ -0,0 +1,128 @@ +name: Parameter Group Version Check + +on: + pull_request: + types: [opened, synchronize, reopened] + branches: + - maintenance-9.x + - maintenance-10.x + paths: + - 'src/**/*.c' + - 'src/**/*.h' + +jobs: + check-pg-versions: + runs-on: ubuntu-latest + permissions: + contents: read + pull-requests: write + + steps: + - name: Checkout PR code + uses: actions/checkout@v4 + with: + fetch-depth: 0 # Need full history to compare with base branch + + - name: Fetch base branch + run: | + git fetch origin ${{ github.base_ref }}:refs/remotes/origin/${{ github.base_ref }} + + - name: Run PG version check script + id: pg_check + run: | + set +e # Don't fail the workflow, just capture exit code + # Run script and capture output. Exit code 1 is expected for issues. + # The output is captured and encoded to be passed between steps. + output=$(bash .github/scripts/check-pg-versions.sh 2>&1) + exit_code=$? + echo "exit_code=${exit_code}" >> $GITHUB_OUTPUT + echo "output<> $GITHUB_OUTPUT + echo "$output" >> $GITHUB_OUTPUT + echo "EOF" >> $GITHUB_OUTPUT + env: + GITHUB_BASE_REF: ${{ github.base_ref }} + GITHUB_HEAD_REF: ${{ github.head_ref }} + + - name: Post comment if issues found + if: steps.pg_check.outputs.exit_code == '1' + uses: actions/github-script@v7 + with: + script: | + // Use the captured output from the previous step + const output = '${{ steps.pg_check.outputs.output }}'; + let issuesContent = ''; + + try { + // Extract issues from output (everything after the warning line) + const lines = output.split('\n'); + let capturing = false; + let issues = []; + + for (const line of lines) { + if (line.includes('###')) { + capturing = true; + } + if (capturing) { + issues.push(line); + } + } + + issuesContent = issues.join('\n'); + } catch (err) { + console.log('Error capturing issues:', err); + issuesContent = '*Unable to extract detailed issues*'; + } + + const commentBody = '## ⚠️ Parameter Group Version Check\n\n' + + 'The following parameter groups may need version increments:\n\n' + + issuesContent + '\n\n' + + '**Why this matters:**\n' + + 'Modifying PG struct fields without incrementing the version can cause settings corruption when users flash new firmware. The `pgLoad()` function validates versions and will use defaults if there\'s a mismatch, preventing corruption.\n\n' + + '**When to increment the version:**\n' + + '- βœ… Adding/removing fields\n' + + '- βœ… Changing field types or sizes\n' + + '- βœ… Reordering fields\n' + + '- βœ… Adding/removing packing attributes\n' + + '- ❌ Only changing default values in `PG_RESET_TEMPLATE`\n' + + '- ❌ Only changing comments\n\n' + + '**Reference:**\n' + + '- [Parameter Group Documentation](../docs/development/parameter_groups/)\n' + + '- Example: [PR #11236](https://github.com/iNavFlight/inav/pull/11236) (field removal requiring version increment)\n\n' + + '---\n' + + '*This is an automated check. False positives are possible. If you believe the version increment is not needed, please explain in a comment.*'; + + try { + // Check if we already commented + const { data: comments } = await github.rest.issues.listComments({ + owner: context.repo.owner, + repo: context.repo.repo, + issue_number: context.issue.number, + }); + + const botComment = comments.find(comment => + comment.user.login === 'github-actions[bot]' && + comment.body.includes('Parameter Group Version Check') + ); + + if (botComment) { + // Update existing comment + await github.rest.issues.updateComment({ + owner: context.repo.owner, + repo: context.repo.repo, + comment_id: botComment.id, + body: commentBody + }); + console.log('Updated existing PG version check comment'); + } else { + // Post new comment + await github.rest.issues.createComment({ + owner: context.repo.owner, + repo: context.repo.repo, + issue_number: context.issue.number, + body: commentBody + }); + console.log('Posted new PG version check comment'); + } + } catch (err) { + core.setFailed(`Failed to post comment: ${err}`); + } diff --git a/AUTHORS b/AUTHORS index 7c2f94fcdb1..010c78e7fed 100644 --- a/AUTHORS +++ b/AUTHORS @@ -81,6 +81,7 @@ Pierre Hugo Richard Birkby Richard Lehey Richard Marko +Ray Morris (Sensei) Rimas Avizienis Sam Cook Sami Korhonen diff --git a/docs/development/msp/msp_ref.md b/docs/development/msp/README.md similarity index 99% rename from docs/development/msp/msp_ref.md rename to docs/development/msp/README.md index d01b978d2eb..5ebefcb6f9d 100644 --- a/docs/development/msp/msp_ref.md +++ b/docs/development/msp/README.md @@ -9,8 +9,21 @@ 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) +**When To Regenerate** -**JSON file rev: 4** +Run `docs/development/msp/gen_docs.sh` whenever MSP docs inputs change: +- `msp_messages.json` message content/schema updates +- source enum changes under `src/main` that affect `inav_enums.json` +- `format.md` or this header template (`docs_v2_header.md`) changes + +By default the script removes temporary generated headers. Use `--keep_headers` only when you need them. + +**Versioning Rule** + +When the MSP JSON specification changes, bump `msp_messages.json` version: +- breaking schema/compatibility change: increment `version.major`, reset `minor` and `patch` +- backward-compatible schema extension: increment `version.minor`, reset `patch` +- message/content/docs-only update inside current schema: increment `version.patch` **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** @@ -28,36 +41,50 @@ For current generation code, see [documentation project](https://github.com/xznh # Format: ## JSON format example: ``` - "MSP_API_VERSION": { - "code": 1, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "mspProtocolVersion", - "ctype": "uint8_t", - "units": "", - "desc": "MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0)." - }, - { - "name": "apiVersionMajor", - "ctype": "uint8_t", - "units": "", - "desc": "INAV API Major version (`API_VERSION_MAJOR`)." - }, - { - "name": "apiVersionMinor", - "ctype": "uint8_t", - "units": "", - "desc": "INAV API Minor version (`API_VERSION_MINOR`)." - } - ], - }, - "notes": "Used by configurators to check compatibility.", - "description": "Provides the MSP protocol version and the INAV API version." +{ + "version": { + "major": 2, + "minor": 0, + "patch": 0 }, + "messages": { + "MSP_API_VERSION": { + "code": 1, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "mspProtocolVersion", + "ctype": "uint8_t", + "units": "", + "desc": "MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0)." + }, + { + "name": "apiVersionMajor", + "ctype": "uint8_t", + "units": "", + "desc": "INAV API Major version (`API_VERSION_MAJOR`)." + }, + { + "name": "apiVersionMinor", + "ctype": "uint8_t", + "units": "", + "desc": "INAV API Minor version (`API_VERSION_MINOR`)." + } + ] + }, + "notes": "Used by configurators to check compatibility.", + "description": "Provides the MSP protocol version and the INAV API version." + }, + "...": {} + } +} ``` +## Top-level fields: +**version**: JSON spec version (`major.minor.patch`)\ +**messages**: Dictionary keyed by MSP message name + ## Message fields: **name**: MSP message name\ **code**: Integer message code\ diff --git a/docs/development/msp/docs_v2_header.md b/docs/development/msp/docs_v2_header.md index 88c057f898e..209b932c486 100644 --- a/docs/development/msp/docs_v2_header.md +++ b/docs/development/msp/docs_v2_header.md @@ -9,8 +9,21 @@ 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) +**When To Regenerate** -**JSON file rev: ** +Run `docs/development/msp/gen_docs.sh` whenever MSP docs inputs change: +- `msp_messages.json` message content/schema updates +- source enum changes under `src/main` that affect `inav_enums.json` +- `format.md` or this header template (`docs_v2_header.md`) changes + +By default the script removes temporary generated headers. Use `--keep_headers` only when you need them. + +**Versioning Rule** + +When the MSP JSON specification changes, bump `msp_messages.json` version: +- breaking schema/compatibility change: increment `version.major`, reset `minor` and `patch` +- backward-compatible schema extension: increment `version.minor`, reset `patch` +- message/content/docs-only update inside current schema: increment `version.patch` **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** diff --git a/docs/development/msp/format.md b/docs/development/msp/format.md index e8c6a348c07..620ab5add53 100644 --- a/docs/development/msp/format.md +++ b/docs/development/msp/format.md @@ -1,36 +1,50 @@ # Format: ## JSON format example: ``` - "MSP_API_VERSION": { - "code": 1, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "mspProtocolVersion", - "ctype": "uint8_t", - "units": "", - "desc": "MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0)." - }, - { - "name": "apiVersionMajor", - "ctype": "uint8_t", - "units": "", - "desc": "INAV API Major version (`API_VERSION_MAJOR`)." - }, - { - "name": "apiVersionMinor", - "ctype": "uint8_t", - "units": "", - "desc": "INAV API Minor version (`API_VERSION_MINOR`)." - } - ], - }, - "notes": "Used by configurators to check compatibility.", - "description": "Provides the MSP protocol version and the INAV API version." +{ + "version": { + "major": 2, + "minor": 0, + "patch": 0 }, + "messages": { + "MSP_API_VERSION": { + "code": 1, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "mspProtocolVersion", + "ctype": "uint8_t", + "units": "", + "desc": "MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0)." + }, + { + "name": "apiVersionMajor", + "ctype": "uint8_t", + "units": "", + "desc": "INAV API Major version (`API_VERSION_MAJOR`)." + }, + { + "name": "apiVersionMinor", + "ctype": "uint8_t", + "units": "", + "desc": "INAV API Minor version (`API_VERSION_MINOR`)." + } + ] + }, + "notes": "Used by configurators to check compatibility.", + "description": "Provides the MSP protocol version and the INAV API version." + }, + "...": {} + } +} ``` +## Top-level fields: +**version**: JSON spec version (`major.minor.patch`)\ +**messages**: Dictionary keyed by MSP message name + ## Message fields: **name**: MSP message name\ **code**: Integer message code\ diff --git a/docs/development/msp/gen_docs.sh b/docs/development/msp/gen_docs.sh index 389d34d114b..581fc3c5fa6 100644 --- a/docs/development/msp/gen_docs.sh +++ b/docs/development/msp/gen_docs.sh @@ -1,27 +1,35 @@ +#!/usr/bin/env bash + +set -euo pipefail + INAV_MAIN_PATH="../../../src/main" +INAV_ROOT="../../.." +BUILD_INFO_SCRIPT="./get_fc_build_info.sh" +KEEP_HEADERS=0 + +for arg in "$@"; do + if [[ "$arg" == "--keep_headers" ]]; then + KEEP_HEADERS=1 + fi +done + +eval "$("$BUILD_INFO_SCRIPT" "$INAV_ROOT")" echo "###########" echo get_all_inav_enums_h.py python get_all_inav_enums_h.py --inav-root "$INAV_MAIN_PATH" -echo "###########" -echo "msp_messages.json checksum" -actual="$(md5sum msp_messages.json | awk '{print $1}')" -expected="$(awk '{print $1}' msp_messages.checksum)" -echo "Hash:" $actual -if [[ "$actual" != "$expected" ]]; then - n="$(cat rev)" - echo $((n + 1)) > rev - echo "File changed, incrementing revision" - echo $actual > msp_messages.checksum -fi - echo "###########" echo gen_msp_md.py python gen_msp_md.py echo "###########" echo gen_enum_md.py -python gen_enum_md.py -rm all_enums.h -read -n 1 -s -r -p "Press any key to continue" +python gen_enum_md.py \ + --fc-version-major "$FC_VERSION_MAJOR" \ + --fc-version-minor "$FC_VERSION_MINOR" \ + --fc-version-patch-level "$FC_VERSION_PATCH_LEVEL" \ + --git-revision "$GIT_REVISION" +if [[ "$KEEP_HEADERS" -eq 0 ]]; then + rm all_enums.h +fi diff --git a/docs/development/msp/gen_enum_md.py b/docs/development/msp/gen_enum_md.py index 64e8d66f756..93fca076e47 100644 --- a/docs/development/msp/gen_enum_md.py +++ b/docs/development/msp/gen_enum_md.py @@ -20,6 +20,7 @@ from pathlib import Path from typing import List, Optional import json +import argparse # ---------- Helpers ---------- @@ -249,7 +250,7 @@ def parse_files(paths: List[Path]) -> List[EnumDef]: # ---------- Markdown rendering ---------- -def render_markdown(enums: List[EnumDef]) -> str: +def render_markdown(enums: List[EnumDef], build: dict) -> str: jsonfile = {} out = [] out.append("# Enumerations\n") @@ -277,19 +278,39 @@ def render_markdown(enums: List[EnumDef]) -> str: if '_source' in jsonfile[e.name]: jsonfile[e.name]['_source'] = jsonfile[e.name]['_source'].replace('../../../src', 'inav/src') out.append("") - # While we're at it, chuck this all into a JSON file - Path("inav_enums.json").write_text(json.dumps(jsonfile,indent=4), encoding="utf-8") + wrapped = { + "build": build, + "enums": jsonfile, + } + Path("inav_enums.json").write_text(json.dumps(wrapped, indent=4), encoding="utf-8") return "\n".join(out) # ---------- Main ---------- def main() -> int: + parser = argparse.ArgumentParser(description="Generate enum markdown/json from all_enums.h") + parser.add_argument("--fc-version-major", required=True, type=int) + parser.add_argument("--fc-version-minor", required=True, type=int) + parser.add_argument("--fc-version-patch-level", required=True, type=int) + parser.add_argument("--git-revision", required=True) + args = parser.parse_args() + path = Path("all_enums.h") if not path.exists(): print(f"Error: {path} not found", file=sys.stderr) return 1 enums = parse_files([path]) - md = render_markdown(enums) + md = render_markdown( + enums, + { + "fc_version": { + "major": args.fc_version_major, + "minor": args.fc_version_minor, + "patch": args.fc_version_patch_level, + }, + "git_revision": args.git_revision, + }, + ) Path("inav_enums_ref.md").write_text(md, encoding="utf-8") return 0 diff --git a/docs/development/msp/gen_msp_md.py b/docs/development/msp/gen_msp_md.py index 7a82a732aa0..8540e5b6b1c 100644 --- a/docs/development/msp/gen_msp_md.py +++ b/docs/development/msp/gen_msp_md.py @@ -8,7 +8,7 @@ - STRICT: If a code exists in one (MSPCodes vs JSON) but not the other, crash with details. - Index items link to headings via GitHub-style auto-anchors. - Tight layout; identical Request/Reply tables; skip complex=true with a stub. -- Default input: msp_messages.json ; default output: MSP_Doc.md +- Default input: msp_messages.json ; default output: README.md """ import sys @@ -414,24 +414,24 @@ def generate_markdown(defs: Dict[str, Any]) -> str: with open("format.md", "r", encoding="utf-8") as f: fmt = f.read() - with open("msp_messages.checksum", "r", encoding="utf-8") as f: - chksum = f.read().split(' ')[0] - with open("rev", "r", encoding="utf-8") as f: - rev = f.read() - - header = header.replace('',fmt) - header = header.replace('',rev) - header = header.replace('',chksum) + header = header.replace('', fmt) index_md = build_index(json_by_code) return header + "\n" + index_md + "\n" + "".join(sections) + +def get_messages_definitions(payload: Dict[str, Any]) -> Dict[str, Any]: + if "messages" in payload: + return payload["messages"] + return payload + def main(): in_path = Path(sys.argv[1]) if len(sys.argv) >= 2 else Path("msp_messages.json") - out_path = Path(sys.argv[2]) if len(sys.argv) >= 3 else Path("msp_ref.md") + out_path = Path(sys.argv[2]) if len(sys.argv) >= 3 else Path("README.md") with in_path.open("r", encoding="utf-8") as f: - defs = json.load(f) + payload = json.load(f) + defs = get_messages_definitions(payload) md = generate_markdown(defs) out_path.write_text(md, encoding="utf-8") diff --git a/docs/development/msp/get_fc_build_info.sh b/docs/development/msp/get_fc_build_info.sh new file mode 100644 index 00000000000..814d6e38cc7 --- /dev/null +++ b/docs/development/msp/get_fc_build_info.sh @@ -0,0 +1,15 @@ +#!/usr/bin/env bash + +set -euo pipefail + +INAV_ROOT="${1:-$(git rev-parse --show-toplevel)}" +CMAKE_FILE="$INAV_ROOT/CMakeLists.txt" + +version_fields="$(sed -nE 's/^project\(INAV VERSION ([0-9]+)\.([0-9]+)\.([0-9]+)\).*/\1 \2 \3/p' "$CMAKE_FILE")" +read -r FC_VERSION_MAJOR FC_VERSION_MINOR FC_VERSION_PATCH_LEVEL <<< "$version_fields" +GIT_REVISION="$(git -C "$INAV_ROOT" rev-parse --short=8 HEAD)" + +printf 'FC_VERSION_MAJOR=%s\n' "$FC_VERSION_MAJOR" +printf 'FC_VERSION_MINOR=%s\n' "$FC_VERSION_MINOR" +printf 'FC_VERSION_PATCH_LEVEL=%s\n' "$FC_VERSION_PATCH_LEVEL" +printf 'GIT_REVISION=%s\n' "$GIT_REVISION" diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json index ebd1fba018a..b4cceb5599c 100644 --- a/docs/development/msp/inav_enums.json +++ b/docs/development/msp/inav_enums.json @@ -1,4128 +1,4138 @@ { - "accelerationSensor_e": { - "_source": "inav/src/main/sensors/acceleration.h", - "ACC_NONE": "0", - "ACC_AUTODETECT": "1", - "ACC_MPU6000": "2", - "ACC_MPU6500": "3", - "ACC_MPU9250": "4", - "ACC_BMI160": "5", - "ACC_ICM20689": "6", - "ACC_BMI088": "7", - "ACC_ICM42605": "8", - "ACC_BMI270": "9", - "ACC_LSM6DXX": "10", - "ACC_FAKE": "11", - "ACC_MAX": "ACC_FAKE" - }, - "accEvent_t": { - "_source": "inav/src/main/telemetry/sim.c", - "ACC_EVENT_NONE": "0", - "ACC_EVENT_HIGH": "1", - "ACC_EVENT_LOW": "2", - "ACC_EVENT_NEG_X": "3" - }, - "adcChannel_e": { - "_source": "inav/src/main/drivers/adc.h", - "ADC_CHN_NONE": "0", - "ADC_CHN_1": "1", - "ADC_CHN_2": "2", - "ADC_CHN_3": "3", - "ADC_CHN_4": "4", - "ADC_CHN_5": "5", - "ADC_CHN_6": "6", - "ADC_CHN_MAX": "ADC_CHN_6", - "ADC_CHN_COUNT": "" - }, - "ADCDevice": { - "_source": "inav/src/main/drivers/adc_impl.h", - "ADCINVALID": "-1", - "ADCDEV_1": "0", - "ADCDEV_2": [ - "(1)", - "STM32F4 || STM32F7 || STM32H7" - ], - "ADCDEV_3": [ - "(2)", - "STM32F4 || STM32F7 || STM32H7" - ], - "ADCDEV_MAX": [ - "ADCDEV_1", - "NOT(STM32F4 || STM32F7 || STM32H7)" - ], - "ADCDEV_COUNT": "ADCDEV_MAX + 1" - }, - "adcFunction_e": { - "_source": "inav/src/main/drivers/adc.h", - "ADC_BATTERY": "0", - "ADC_RSSI": "1", - "ADC_CURRENT": "2", - "ADC_AIRSPEED": "3", - "ADC_FUNCTION_COUNT": "4" - }, - "adjustmentFunction_e": { - "_source": "inav/src/main/fc/rc_adjustments.h", - "ADJUSTMENT_NONE": "0", - "ADJUSTMENT_RC_RATE": "1", - "ADJUSTMENT_RC_EXPO": "2", - "ADJUSTMENT_THROTTLE_EXPO": "3", - "ADJUSTMENT_PITCH_ROLL_RATE": "4", - "ADJUSTMENT_YAW_RATE": "5", - "ADJUSTMENT_PITCH_ROLL_P": "6", - "ADJUSTMENT_PITCH_ROLL_I": "7", - "ADJUSTMENT_PITCH_ROLL_D": "8", - "ADJUSTMENT_PITCH_ROLL_FF": "9", - "ADJUSTMENT_PITCH_P": "10", - "ADJUSTMENT_PITCH_I": "11", - "ADJUSTMENT_PITCH_D": "12", - "ADJUSTMENT_PITCH_FF": "13", - "ADJUSTMENT_ROLL_P": "14", - "ADJUSTMENT_ROLL_I": "15", - "ADJUSTMENT_ROLL_D": "16", - "ADJUSTMENT_ROLL_FF": "17", - "ADJUSTMENT_YAW_P": "18", - "ADJUSTMENT_YAW_I": "19", - "ADJUSTMENT_YAW_D": "20", - "ADJUSTMENT_YAW_FF": "21", - "ADJUSTMENT_RATE_PROFILE": "22", - "ADJUSTMENT_PITCH_RATE": "23", - "ADJUSTMENT_ROLL_RATE": "24", - "ADJUSTMENT_RC_YAW_EXPO": "25", - "ADJUSTMENT_MANUAL_RC_EXPO": "26", - "ADJUSTMENT_MANUAL_RC_YAW_EXPO": "27", - "ADJUSTMENT_MANUAL_PITCH_ROLL_RATE": "28", - "ADJUSTMENT_MANUAL_ROLL_RATE": "29", - "ADJUSTMENT_MANUAL_PITCH_RATE": "30", - "ADJUSTMENT_MANUAL_YAW_RATE": "31", - "ADJUSTMENT_NAV_FW_CRUISE_THR": "32", - "ADJUSTMENT_NAV_FW_PITCH2THR": "33", - "ADJUSTMENT_ROLL_BOARD_ALIGNMENT": "34", - "ADJUSTMENT_PITCH_BOARD_ALIGNMENT": "35", - "ADJUSTMENT_LEVEL_P": "36", - "ADJUSTMENT_LEVEL_I": "37", - "ADJUSTMENT_LEVEL_D": "38", - "ADJUSTMENT_POS_XY_P": "39", - "ADJUSTMENT_POS_XY_I": "40", - "ADJUSTMENT_POS_XY_D": "41", - "ADJUSTMENT_POS_Z_P": "42", - "ADJUSTMENT_POS_Z_I": "43", - "ADJUSTMENT_POS_Z_D": "44", - "ADJUSTMENT_HEADING_P": "45", - "ADJUSTMENT_VEL_XY_P": "46", - "ADJUSTMENT_VEL_XY_I": "47", - "ADJUSTMENT_VEL_XY_D": "48", - "ADJUSTMENT_VEL_Z_P": "49", - "ADJUSTMENT_VEL_Z_I": "50", - "ADJUSTMENT_VEL_Z_D": "51", - "ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "52", - "ADJUSTMENT_VTX_POWER_LEVEL": "53", - "ADJUSTMENT_TPA": "54", - "ADJUSTMENT_TPA_BREAKPOINT": "55", - "ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS": "56", - "ADJUSTMENT_FW_TPA_TIME_CONSTANT": "57", - "ADJUSTMENT_FW_LEVEL_TRIM": "58", - "ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX": "59", - "ADJUSTMENT_NAV_FW_ALT_CONTROL_RESPONSE": "60", - "ADJUSTMENT_FUNCTION_COUNT": "61" - }, - "adjustmentMode_e": { - "_source": "inav/src/main/fc/rc_adjustments.h", - "ADJUSTMENT_MODE_STEP": "0", - "ADJUSTMENT_MODE_SELECT": "1" - }, - "afatfsAppendFreeClusterPhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_INITIAL": "0", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_FIND_FREESPACE": "0", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT1": "1", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT2": "2", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_COMPLETE": "4", - "AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE": "5" - }, - "afatfsAppendSuperclusterPhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_APPEND_SUPERCLUSTER_PHASE_INIT": "0", - "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FREEFILE_DIRECTORY": "1", - "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FAT": "2", - "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3" - }, - "afatfsCacheBlockState_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_CACHE_STATE_EMPTY": "0", - "AFATFS_CACHE_STATE_IN_SYNC": "1", - "AFATFS_CACHE_STATE_READING": "2", - "AFATFS_CACHE_STATE_WRITING": "3", - "AFATFS_CACHE_STATE_DIRTY": "4" - }, - "afatfsClusterSearchCondition_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "CLUSTER_SEARCH_FREE_AT_BEGINNING_OF_FAT_SECTOR": "0", - "CLUSTER_SEARCH_FREE": "1", - "CLUSTER_SEARCH_OCCUPIED": "2" - }, - "afatfsDeleteFilePhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY": "0", - "AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS": "1" - }, - "afatfsError_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", - "AFATFS_ERROR_NONE": "0", - "AFATFS_ERROR_GENERIC": "1", - "AFATFS_ERROR_BAD_MBR": "2", - "AFATFS_ERROR_BAD_FILESYSTEM_HEADER": "3" - }, - "afatfsExtendSubdirectoryPhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_EXTEND_SUBDIRECTORY_PHASE_INITIAL": "0", - "AFATFS_EXTEND_SUBDIRECTORY_PHASE_ADD_FREE_CLUSTER": "0", - "AFATFS_EXTEND_SUBDIRECTORY_PHASE_WRITE_SECTORS": "1", - "AFATFS_EXTEND_SUBDIRECTORY_PHASE_SUCCESS": "2", - "AFATFS_EXTEND_SUBDIRECTORY_PHASE_FAILURE": "3" - }, - "afatfsFATPattern_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_FAT_PATTERN_UNTERMINATED_CHAIN": "0", - "AFATFS_FAT_PATTERN_TERMINATED_CHAIN": "1", - "AFATFS_FAT_PATTERN_FREE": "2" - }, - "afatfsFileOperation_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_FILE_OPERATION_NONE": "0", - "AFATFS_FILE_OPERATION_CREATE_FILE": "1", - "AFATFS_FILE_OPERATION_SEEK": "2", - "AFATFS_FILE_OPERATION_CLOSE": "3", - "AFATFS_FILE_OPERATION_TRUNCATE": "4", - "AFATFS_FILE_OPERATION_UNLINK": "5", - "AFATFS_FILE_OPERATION_APPEND_SUPERCLUSTER": [ - "(6)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_FILE_OPERATION_LOCKED": [ - "(7)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_FILE_OPERATION_APPEND_FREE_CLUSTER": "8", - "AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY": "9" - }, - "afatfsFilesystemState_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", - "AFATFS_FILESYSTEM_STATE_UNKNOWN": "0", - "AFATFS_FILESYSTEM_STATE_FATAL": "1", - "AFATFS_FILESYSTEM_STATE_INITIALIZATION": "2", - "AFATFS_FILESYSTEM_STATE_READY": "3" - }, - "afatfsFileType_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_FILE_TYPE_NONE": "0", - "AFATFS_FILE_TYPE_NORMAL": "1", - "AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY": "2", - "AFATFS_FILE_TYPE_DIRECTORY": "3" - }, - "afatfsFindClusterStatus_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_FIND_CLUSTER_IN_PROGRESS": "0", - "AFATFS_FIND_CLUSTER_FOUND": "1", - "AFATFS_FIND_CLUSTER_FATAL": "2", - "AFATFS_FIND_CLUSTER_NOT_FOUND": "3" - }, - "afatfsFreeSpaceSearchPhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_FREE_SPACE_SEARCH_PHASE_FIND_HOLE": "0", - "AFATFS_FREE_SPACE_SEARCH_PHASE_GROW_HOLE": "1" - }, - "afatfsInitializationPhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_INITIALIZATION_READ_MBR": "0", - "AFATFS_INITIALIZATION_READ_VOLUME_ID": "1", - "AFATFS_INITIALIZATION_FREEFILE_CREATE": [ - "(2)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_INITIALIZATION_FREEFILE_CREATING": [ - "(3)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_INITIALIZATION_FREEFILE_FAT_SEARCH": [ - "(4)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_INITIALIZATION_FREEFILE_UPDATE_FAT": [ - "(5)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY": [ - "(6)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_INITIALIZATION_FREEFILE_LAST": [ - "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_INITIALIZATION_DONE": "" - }, - "afatfsOperationStatus_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", - "AFATFS_OPERATION_IN_PROGRESS": "0", - "AFATFS_OPERATION_SUCCESS": "1", - "AFATFS_OPERATION_FAILURE": "2" - }, - "afatfsSaveDirectoryEntryMode_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_SAVE_DIRECTORY_NORMAL": "0", - "AFATFS_SAVE_DIRECTORY_FOR_CLOSE": "1", - "AFATFS_SAVE_DIRECTORY_DELETED": "2" - }, - "afatfsSeek_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", - "AFATFS_SEEK_SET": "0", - "AFATFS_SEEK_CUR": "1", - "AFATFS_SEEK_END": "2" - }, - "afatfsTruncateFilePhase_e": { - "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", - "AFATFS_TRUNCATE_FILE_INITIAL": "0", - "AFATFS_TRUNCATE_FILE_UPDATE_DIRECTORY": "0", - "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_NORMAL": "1", - "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_CONTIGUOUS": [ - "(2)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_TRUNCATE_FILE_PREPEND_TO_FREEFILE": [ - "(3)", - "AFATFS_USE_FREEFILE" - ], - "AFATFS_TRUNCATE_FILE_SUCCESS": "4" - }, - "airmodeHandlingType_e": { - "_source": "inav/src/main/fc/rc_controls.h", - "STICK_CENTER": "0", - "THROTTLE_THRESHOLD": "1", - "STICK_CENTER_ONCE": "2" - }, - "angle_index_t": { - "_source": "inav/src/main/common/axis.h", - "AI_ROLL": "0", - "AI_PITCH": "1" - }, - "armingFlag_e": { - "_source": "inav/src/main/fc/runtime_config.h", - "ARMED": "(1 << 2)", - "WAS_EVER_ARMED": "(1 << 3)", - "SIMULATOR_MODE_HITL": "(1 << 4)", - "SIMULATOR_MODE_SITL": "(1 << 5)", - "ARMING_DISABLED_GEOZONE": "(1 << 6)", - "ARMING_DISABLED_FAILSAFE_SYSTEM": "(1 << 7)", - "ARMING_DISABLED_NOT_LEVEL": "(1 << 8)", - "ARMING_DISABLED_SENSORS_CALIBRATING": "(1 << 9)", - "ARMING_DISABLED_SYSTEM_OVERLOADED": "(1 << 10)", - "ARMING_DISABLED_NAVIGATION_UNSAFE": "(1 << 11)", - "ARMING_DISABLED_COMPASS_NOT_CALIBRATED": "(1 << 12)", - "ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED": "(1 << 13)", - "ARMING_DISABLED_ARM_SWITCH": "(1 << 14)", - "ARMING_DISABLED_HARDWARE_FAILURE": "(1 << 15)", - "ARMING_DISABLED_BOXFAILSAFE": "(1 << 16)", - "ARMING_DISABLED_RC_LINK": "(1 << 18)", - "ARMING_DISABLED_THROTTLE": "(1 << 19)", - "ARMING_DISABLED_CLI": "(1 << 20)", - "ARMING_DISABLED_CMS_MENU": "(1 << 21)", - "ARMING_DISABLED_OSD_MENU": "(1 << 22)", - "ARMING_DISABLED_ROLLPITCH_NOT_CENTERED": "(1 << 23)", - "ARMING_DISABLED_SERVO_AUTOTRIM": "(1 << 24)", - "ARMING_DISABLED_OOM": "(1 << 25)", - "ARMING_DISABLED_INVALID_SETTING": "(1 << 26)", - "ARMING_DISABLED_PWM_OUTPUT_ERROR": "(1 << 27)", - "ARMING_DISABLED_NO_PREARM": "(1 << 28)", - "ARMING_DISABLED_DSHOT_BEEPER": "(1 << 29)", - "ARMING_DISABLED_LANDING_DETECTED": "(1 << 30)", - "ARMING_DISABLED_ALL_FLAGS": "(ARMING_DISABLED_GEOZONE | ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED | ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING | ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER | ARMING_DISABLED_LANDING_DETECTED)" - }, - "axis_e": { - "_source": "inav/src/main/common/axis.h", - "X": "0", - "Y": "1", - "Z": "2" - }, - "barometerState_e": { - "_source": "inav/src/main/sensors/barometer.c", - "BAROMETER_NEEDS_SAMPLES": "0", - "BAROMETER_NEEDS_CALCULATION": "1" - }, - "baroSensor_e": { - "_source": "inav/src/main/sensors/barometer.h", - "BARO_NONE": "0", - "BARO_AUTODETECT": "1", - "BARO_BMP085": "2", - "BARO_MS5611": "3", - "BARO_BMP280": "4", - "BARO_MS5607": "5", - "BARO_LPS25H": "6", - "BARO_SPL06": "7", - "BARO_BMP388": "8", - "BARO_DPS310": "9", - "BARO_B2SMPB": "10", - "BARO_MSP": "11", - "BARO_FAKE": "12", - "BARO_MAX": "BARO_FAKE" - }, - "batCapacityUnit_e": { - "_source": "inav/src/main/sensors/battery_config_structs.h", - "BAT_CAPACITY_UNIT_MAH": "0", - "BAT_CAPACITY_UNIT_MWH": "1" - }, - "batteryState_e": { - "_source": "inav/src/main/sensors/battery.h", - "BATTERY_OK": "0", - "BATTERY_WARNING": "1", - "BATTERY_CRITICAL": "2", - "BATTERY_NOT_PRESENT": "3" - }, - "batVoltageSource_e": { - "_source": "inav/src/main/sensors/battery_config_structs.h", - "BAT_VOLTAGE_RAW": "0", - "BAT_VOLTAGE_SAG_COMP": "1" - }, - "baudRate_e": { - "_source": "inav/src/main/io/serial.h", - "BAUD_AUTO": "0", - "BAUD_1200": "1", - "BAUD_2400": "2", - "BAUD_4800": "3", - "BAUD_9600": "4", - "BAUD_19200": "5", - "BAUD_38400": "6", - "BAUD_57600": "7", - "BAUD_115200": "8", - "BAUD_230400": "9", - "BAUD_250000": "10", - "BAUD_460800": "11", - "BAUD_921600": "12", - "BAUD_1000000": "13", - "BAUD_1500000": "14", - "BAUD_2000000": "15", - "BAUD_2470000": "16", - "BAUD_MIN": "BAUD_AUTO", - "BAUD_MAX": "BAUD_2470000" - }, - "beeperMode_e": { - "_source": "inav/src/main/io/beeper.h", - "BEEPER_SILENCE": "0", - "BEEPER_RUNTIME_CALIBRATION_DONE": "1", - "BEEPER_HARDWARE_FAILURE": "2", - "BEEPER_RX_LOST": "3", - "BEEPER_RX_LOST_LANDING": "4", - "BEEPER_DISARMING": "5", - "BEEPER_ARMING": "6", - "BEEPER_ARMING_GPS_FIX": "7", - "BEEPER_BAT_CRIT_LOW": "8", - "BEEPER_BAT_LOW": "9", - "BEEPER_GPS_STATUS": "10", - "BEEPER_RX_SET": "11", - "BEEPER_ACTION_SUCCESS": "12", - "BEEPER_ACTION_FAIL": "13", - "BEEPER_READY_BEEP": "14", - "BEEPER_MULTI_BEEPS": "15", - "BEEPER_DISARM_REPEAT": "16", - "BEEPER_ARMED": "17", - "BEEPER_SYSTEM_INIT": "18", - "BEEPER_USB": "19", - "BEEPER_LAUNCH_MODE_ENABLED": "20", - "BEEPER_LAUNCH_MODE_LOW_THROTTLE": "21", - "BEEPER_LAUNCH_MODE_IDLE_START": "22", - "BEEPER_CAM_CONNECTION_OPEN": "23", - "BEEPER_CAM_CONNECTION_CLOSE": "24", - "BEEPER_ALL": "25", - "BEEPER_PREFERENCE": "26" - }, - "biquadFilterType_e": { - "_source": "inav/src/main/common/filter.h", - "FILTER_LPF": "0", - "FILTER_NOTCH": "1" - }, - "blackboxBufferReserveStatus_e": { - "_source": "inav/src/main/blackbox/blackbox_io.h", - "BLACKBOX_RESERVE_SUCCESS": "0", - "BLACKBOX_RESERVE_TEMPORARY_FAILURE": "1", - "BLACKBOX_RESERVE_PERMANENT_FAILURE": "2" - }, - "BlackboxDevice": { - "_source": "inav/src/main/blackbox/blackbox_io.h", - "BLACKBOX_DEVICE_SERIAL": "0", - "BLACKBOX_DEVICE_FLASH": [ - "1", - "USE_FLASHFS" - ], - "BLACKBOX_DEVICE_SDCARD": [ - "2", - "USE_SDCARD" - ], - "BLACKBOX_DEVICE_FILE": [ - "3", - "SITL_BUILD" - ], - "BLACKBOX_DEVICE_END": "4" - }, - "blackboxFeatureMask_e": { - "_source": "inav/src/main/blackbox/blackbox.h", - "BLACKBOX_FEATURE_NAV_ACC": "1 << 0", - "BLACKBOX_FEATURE_NAV_POS": "1 << 1", - "BLACKBOX_FEATURE_NAV_PID": "1 << 2", - "BLACKBOX_FEATURE_MAG": "1 << 3", - "BLACKBOX_FEATURE_ACC": "1 << 4", - "BLACKBOX_FEATURE_ATTITUDE": "1 << 5", - "BLACKBOX_FEATURE_RC_DATA": "1 << 6", - "BLACKBOX_FEATURE_RC_COMMAND": "1 << 7", - "BLACKBOX_FEATURE_MOTORS": "1 << 8", - "BLACKBOX_FEATURE_GYRO_RAW": "1 << 9", - "BLACKBOX_FEATURE_GYRO_PEAKS_ROLL": "1 << 10", - "BLACKBOX_FEATURE_GYRO_PEAKS_PITCH": "1 << 11", - "BLACKBOX_FEATURE_GYRO_PEAKS_YAW": "1 << 12", - "BLACKBOX_FEATURE_SERVOS": "1 << 13" - }, - "BlackboxState": { - "_source": "inav/src/main/blackbox/blackbox.h", - "BLACKBOX_STATE_DISABLED": "0", - "BLACKBOX_STATE_STOPPED": "1", - "BLACKBOX_STATE_PREPARE_LOG_FILE": "2", - "BLACKBOX_STATE_SEND_HEADER": "3", - "BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER": "4", - "BLACKBOX_STATE_SEND_GPS_H_HEADER": "5", - "BLACKBOX_STATE_SEND_GPS_G_HEADER": "6", - "BLACKBOX_STATE_SEND_SLOW_HEADER": "7", - "BLACKBOX_STATE_SEND_SYSINFO": "8", - "BLACKBOX_STATE_PAUSED": "9", - "BLACKBOX_STATE_RUNNING": "10", - "BLACKBOX_STATE_SHUTTING_DOWN": "11" - }, - "bmi270Register_e": { - "_source": "inav/src/main/drivers/accgyro/accgyro_bmi270.c", - "BMI270_REG_CHIP_ID": "0", - "BMI270_REG_ERR_REG": "2", - "BMI270_REG_STATUS": "3", - "BMI270_REG_ACC_DATA_X_LSB": "12", - "BMI270_REG_GYR_DATA_X_LSB": "18", - "BMI270_REG_SENSORTIME_0": "24", - "BMI270_REG_SENSORTIME_1": "25", - "BMI270_REG_SENSORTIME_2": "26", - "BMI270_REG_EVENT": "27", - "BMI270_REG_INT_STATUS_0": "28", - "BMI270_REG_INT_STATUS_1": "29", - "BMI270_REG_INTERNAL_STATUS": "33", - "BMI270_REG_TEMPERATURE_LSB": "34", - "BMI270_REG_TEMPERATURE_MSB": "35", - "BMI270_REG_FIFO_LENGTH_LSB": "36", - "BMI270_REG_FIFO_LENGTH_MSB": "37", - "BMI270_REG_FIFO_DATA": "38", - "BMI270_REG_ACC_CONF": "64", - "BMI270_REG_ACC_RANGE": "65", - "BMI270_REG_GYRO_CONF": "66", - "BMI270_REG_GYRO_RANGE": "67", - "BMI270_REG_AUX_CONF": "68", - "BMI270_REG_FIFO_DOWNS": "69", - "BMI270_REG_FIFO_WTM_0": "70", - "BMI270_REG_FIFO_WTM_1": "71", - "BMI270_REG_FIFO_CONFIG_0": "72", - "BMI270_REG_FIFO_CONFIG_1": "73", - "BMI270_REG_SATURATION": "74", - "BMI270_REG_INT1_IO_CTRL": "83", - "BMI270_REG_INT2_IO_CTRL": "84", - "BMI270_REG_INT_LATCH": "85", - "BMI270_REG_INT1_MAP_FEAT": "86", - "BMI270_REG_INT2_MAP_FEAT": "87", - "BMI270_REG_INT_MAP_DATA": "88", - "BMI270_REG_INIT_CTRL": "89", - "BMI270_REG_INIT_DATA": "94", - "BMI270_REG_ACC_SELF_TEST": "109", - "BMI270_REG_GYR_SELF_TEST_AXES": "110", - "BMI270_REG_PWR_CONF": "124", - "BMI270_REG_PWR_CTRL": "125", - "BMI270_REG_CMD": "126" - }, - "bootLogEventCode_e": { - "_source": "inav/src/main/drivers/logging_codes.h", - "BOOT_EVENT_CONFIG_LOADED": "0", - "BOOT_EVENT_SYSTEM_INIT_DONE": "1", - "BOOT_EVENT_PWM_INIT_DONE": "2", - "BOOT_EVENT_EXTRA_BOOT_DELAY": "3", - "BOOT_EVENT_SENSOR_INIT_DONE": "4", - "BOOT_EVENT_GPS_INIT_DONE": "5", - "BOOT_EVENT_LEDSTRIP_INIT_DONE": "6", - "BOOT_EVENT_TELEMETRY_INIT_DONE": "7", - "BOOT_EVENT_SYSTEM_READY": "8", - "BOOT_EVENT_GYRO_DETECTION": "9", - "BOOT_EVENT_ACC_DETECTION": "10", - "BOOT_EVENT_BARO_DETECTION": "11", - "BOOT_EVENT_MAG_DETECTION": "12", - "BOOT_EVENT_RANGEFINDER_DETECTION": "13", - "BOOT_EVENT_MAG_INIT_FAILED": "14", - "BOOT_EVENT_HMC5883L_READ_OK_COUNT": "15", - "BOOT_EVENT_HMC5883L_READ_FAILED": "16", - "BOOT_EVENT_HMC5883L_SATURATION": "17", - "BOOT_EVENT_TIMER_CH_SKIPPED": "18", - "BOOT_EVENT_TIMER_CH_MAPPED": "19", - "BOOT_EVENT_PITOT_DETECTION": "20", - "BOOT_EVENT_TEMP_SENSOR_DETECTION": "21", - "BOOT_EVENT_1WIRE_DETECTION": "22", - "BOOT_EVENT_HARDWARE_IO_CONFLICT": "23", - "BOOT_EVENT_OPFLOW_DETECTION": "24", - "BOOT_EVENT_CODE_COUNT": "25" - }, - "bootLogFlags_e": { - "_source": "inav/src/main/drivers/logging_codes.h", - "BOOT_EVENT_FLAGS_NONE": "0", - "BOOT_EVENT_FLAGS_WARNING": "1 << 0", - "BOOT_EVENT_FLAGS_ERROR": "1 << 1", - "BOOT_EVENT_FLAGS_PARAM16": "1 << 14", - "BOOT_EVENT_FLAGS_PARAM32": "1 << 15" - }, - "boxId_e": { - "_source": "inav/src/main/fc/rc_modes.h", - "BOXARM": "0", - "BOXANGLE": "1", - "BOXHORIZON": "2", - "BOXNAVALTHOLD": "3", - "BOXHEADINGHOLD": "4", - "BOXHEADFREE": "5", - "BOXHEADADJ": "6", - "BOXCAMSTAB": "7", - "BOXNAVRTH": "8", - "BOXNAVPOSHOLD": "9", - "BOXMANUAL": "10", - "BOXBEEPERON": "11", - "BOXLEDLOW": "12", - "BOXLIGHTS": "13", - "BOXNAVLAUNCH": "14", - "BOXOSD": "15", - "BOXTELEMETRY": "16", - "BOXBLACKBOX": "17", - "BOXFAILSAFE": "18", - "BOXNAVWP": "19", - "BOXAIRMODE": "20", - "BOXHOMERESET": "21", - "BOXGCSNAV": "22", - "BOXSURFACE": "24", - "BOXFLAPERON": "25", - "BOXTURNASSIST": "26", - "BOXAUTOTRIM": "27", - "BOXAUTOTUNE": "28", - "BOXCAMERA1": "29", - "BOXCAMERA2": "30", - "BOXCAMERA3": "31", - "BOXOSDALT1": "32", - "BOXOSDALT2": "33", - "BOXOSDALT3": "34", - "BOXNAVCOURSEHOLD": "35", - "BOXBRAKING": "36", - "BOXUSER1": "37", - "BOXUSER2": "38", - "BOXFPVANGLEMIX": "39", - "BOXLOITERDIRCHN": "40", - "BOXMSPRCOVERRIDE": "41", - "BOXPREARM": "42", - "BOXTURTLE": "43", - "BOXNAVCRUISE": "44", - "BOXAUTOLEVEL": "45", - "BOXPLANWPMISSION": "46", - "BOXSOARING": "47", - "BOXUSER3": "48", - "BOXUSER4": "49", - "BOXCHANGEMISSION": "50", - "BOXBEEPERMUTE": "51", - "BOXMULTIFUNCTION": "52", - "BOXMIXERPROFILE": "53", - "BOXMIXERTRANSITION": "54", - "BOXANGLEHOLD": "55", - "BOXGIMBALTLOCK": "56", - "BOXGIMBALRLOCK": "57", - "BOXGIMBALCENTER": "58", - "BOXGIMBALHTRK": "59", - "CHECKBOX_ITEM_COUNT": "60" - }, - "busIndex_e": { - "_source": "inav/src/main/drivers/bus.h", - "BUSINDEX_1": "0", - "BUSINDEX_2": "1", - "BUSINDEX_3": "2", - "BUSINDEX_4": "3" - }, - "busSpeed_e": { - "_source": "inav/src/main/drivers/bus.h", - "BUS_SPEED_INITIALIZATION": "0", - "BUS_SPEED_SLOW": "1", - "BUS_SPEED_STANDARD": "2", - "BUS_SPEED_FAST": "3", - "BUS_SPEED_ULTRAFAST": "4" - }, - "busType_e": { - "_source": "inav/src/main/drivers/bus.h", - "BUSTYPE_ANY": "0", - "BUSTYPE_NONE": "0", - "BUSTYPE_I2C": "1", - "BUSTYPE_SPI": "2", - "BUSTYPE_SDIO": "3" - }, - "channelType_t": { - "_source": "inav/src/main/drivers/timer.h", - "TYPE_FREE": "0", - "TYPE_PWMINPUT": "1", - "TYPE_PPMINPUT": "2", - "TYPE_PWMOUTPUT_MOTOR": "3", - "TYPE_PWMOUTPUT_FAST": "4", - "TYPE_PWMOUTPUT_SERVO": "5", - "TYPE_SOFTSERIAL_RX": "6", - "TYPE_SOFTSERIAL_TX": "7", - "TYPE_SOFTSERIAL_RXTX": "8", - "TYPE_SOFTSERIAL_AUXTIMER": "9", - "TYPE_ADC": "10", - "TYPE_SERIAL_RX": "11", - "TYPE_SERIAL_TX": "12", - "TYPE_SERIAL_RXTX": "13", - "TYPE_TIMER": "14" - }, - "climbRateToAltitudeControllerMode_e": { - "_source": "inav/src/main/navigation/navigation_private.h", - "ROC_TO_ALT_CURRENT": "0", - "ROC_TO_ALT_CONSTANT": "1", - "ROC_TO_ALT_TARGET": "2" - }, - "colorComponent_e": { - "_source": "inav/src/main/common/color.h", - "RGB_RED": "0", - "RGB_GREEN": "1", - "RGB_BLUE": "2" - }, - "colorId_e": { - "_source": "inav/src/main/io/ledstrip.h", - "COLOR_BLACK": "0", - "COLOR_WHITE": "1", - "COLOR_RED": "2", - "COLOR_ORANGE": "3", - "COLOR_YELLOW": "4", - "COLOR_LIME_GREEN": "5", - "COLOR_GREEN": "6", - "COLOR_MINT_GREEN": "7", - "COLOR_CYAN": "8", - "COLOR_LIGHT_BLUE": "9", - "COLOR_BLUE": "10", - "COLOR_DARK_VIOLET": "11", - "COLOR_MAGENTA": "12", - "COLOR_DEEP_PINK": "13" - }, - "crsfActiveAntenna_e": { - "_source": "inav/src/main/telemetry/crsf.c", - "CRSF_ACTIVE_ANTENNA1": "0", - "CRSF_ACTIVE_ANTENNA2": "1" - }, - "crsfAddress_e": { - "_source": "inav/src/main/rx/crsf.h", - "CRSF_ADDRESS_BROADCAST": "0", - "CRSF_ADDRESS_USB": "16", - "CRSF_ADDRESS_TBS_CORE_PNP_PRO": "128", - "CRSF_ADDRESS_RESERVED1": "138", - "CRSF_ADDRESS_CURRENT_SENSOR": "192", - "CRSF_ADDRESS_GPS": "194", - "CRSF_ADDRESS_TBS_BLACKBOX": "196", - "CRSF_ADDRESS_FLIGHT_CONTROLLER": "200", - "CRSF_ADDRESS_RESERVED2": "202", - "CRSF_ADDRESS_RACE_TAG": "204", - "CRSF_ADDRESS_RADIO_TRANSMITTER": "234", - "CRSF_ADDRESS_CRSF_RECEIVER": "236", - "CRSF_ADDRESS_CRSF_TRANSMITTER": "238" - }, - "crsfFrameType_e": { - "_source": "inav/src/main/rx/crsf.h", - "CRSF_FRAMETYPE_GPS": "2", - "CRSF_FRAMETYPE_VARIO_SENSOR": "7", - "CRSF_FRAMETYPE_BATTERY_SENSOR": "8", - "CRSF_FRAMETYPE_BAROMETER_ALTITUDE": "9", - "CRSF_FRAMETYPE_LINK_STATISTICS": "20", - "CRSF_FRAMETYPE_RC_CHANNELS_PACKED": "22", - "CRSF_FRAMETYPE_ATTITUDE": "30", - "CRSF_FRAMETYPE_FLIGHT_MODE": "33", - "CRSF_FRAMETYPE_DEVICE_PING": "40", - "CRSF_FRAMETYPE_DEVICE_INFO": "41", - "CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY": "43", - "CRSF_FRAMETYPE_PARAMETER_READ": "44", - "CRSF_FRAMETYPE_PARAMETER_WRITE": "45", - "CRSF_FRAMETYPE_COMMAND": "50", - "CRSF_FRAMETYPE_MSP_REQ": "122", - "CRSF_FRAMETYPE_MSP_RESP": "123", - "CRSF_FRAMETYPE_MSP_WRITE": "124", - "CRSF_FRAMETYPE_DISPLAYPORT_CMD": "125" - }, - "crsfFrameTypeIndex_e": { - "_source": "inav/src/main/telemetry/crsf.c", - "CRSF_FRAME_START_INDEX": "0", - "CRSF_FRAME_ATTITUDE_INDEX": "CRSF_FRAME_START_INDEX", - "CRSF_FRAME_BATTERY_SENSOR_INDEX": "", - "CRSF_FRAME_FLIGHT_MODE_INDEX": "", - "CRSF_FRAME_GPS_INDEX": "", - "CRSF_FRAME_VARIO_SENSOR_INDEX": "", - "CRSF_FRAME_BAROMETER_ALTITUDE_INDEX": "", - "CRSF_SCHEDULE_COUNT_MAX": "" - }, - "crsrRfMode_e": { - "_source": "inav/src/main/telemetry/crsf.c", - "CRSF_RF_MODE_4_HZ": "0", - "CRSF_RF_MODE_50_HZ": "1", - "CRSF_RF_MODE_150_HZ": "2" - }, - "crsrRfPower_e": { - "_source": "inav/src/main/telemetry/crsf.c", - "CRSF_RF_POWER_0_mW": "0", - "CRSF_RF_POWER_10_mW": "1", - "CRSF_RF_POWER_25_mW": "2", - "CRSF_RF_POWER_100_mW": "3", - "CRSF_RF_POWER_500_mW": "4", - "CRSF_RF_POWER_1000_mW": "5", - "CRSF_RF_POWER_2000_mW": "6", - "CRSF_RF_POWER_250_mW": "7" - }, - "currentSensor_e": { - "_source": "inav/src/main/sensors/battery_config_structs.h", - "CURRENT_SENSOR_NONE": "0", - "CURRENT_SENSOR_ADC": "1", - "CURRENT_SENSOR_VIRTUAL": "2", - "CURRENT_SENSOR_FAKE": "3", - "CURRENT_SENSOR_ESC": "4", - "CURRENT_SENSOR_SMARTPORT": "5", - "CURRENT_SENSOR_MAX": "CURRENT_SENSOR_SMARTPORT" - }, - "devHardwareType_e": { - "_source": "inav/src/main/drivers/bus.h", - "DEVHW_NONE": "0", - "DEVHW_MPU6000": "1", - "DEVHW_MPU6500": "2", - "DEVHW_BMI160": "3", - "DEVHW_BMI088_GYRO": "4", - "DEVHW_BMI088_ACC": "5", - "DEVHW_ICM20689": "6", - "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" - }, - "deviceFlags_e": { - "_source": "inav/src/main/drivers/bus.h", - "DEVFLAGS_NONE": "0", - "DEVFLAGS_USE_RAW_REGISTERS": "(1 << 0)", - "DEVFLAGS_USE_MANUAL_DEVICE_SELECT": "(1 << 1)", - "DEVFLAGS_SPI_MODE_0": "(1 << 2)" - }, - "disarmReason_t": { - "_source": "inav/src/main/fc/fc_core.h", - "DISARM_NONE": "0", - "DISARM_TIMEOUT": "1", - "DISARM_STICKS": "2", - "DISARM_SWITCH_3D": "3", - "DISARM_SWITCH": "4", - "DISARM_FAILSAFE": "6", - "DISARM_NAVIGATION": "7", - "DISARM_LANDING": "8", - "DISARM_REASON_COUNT": "9" - }, - "displayCanvasBitmapOption_t": { - "_source": "inav/src/main/drivers/display_canvas.h", - "DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS": "1 << 0", - "DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND": "1 << 1", - "DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT": "1 << 2" - }, - "displayCanvasColor_e": { - "_source": "inav/src/main/drivers/display_canvas.h", - "DISPLAY_CANVAS_COLOR_BLACK": "0", - "DISPLAY_CANVAS_COLOR_TRANSPARENT": "1", - "DISPLAY_CANVAS_COLOR_WHITE": "2", - "DISPLAY_CANVAS_COLOR_GRAY": "3" - }, - "displayCanvasOutlineType_e": { - "_source": "inav/src/main/drivers/display_canvas.h", - "DISPLAY_CANVAS_OUTLINE_TYPE_NONE": "0", - "DISPLAY_CANVAS_OUTLINE_TYPE_TOP": "1 << 0", - "DISPLAY_CANVAS_OUTLINE_TYPE_RIGHT": "1 << 1", - "DISPLAY_CANVAS_OUTLINE_TYPE_BOTTOM": "1 << 2", - "DISPLAY_CANVAS_OUTLINE_TYPE_LEFT": "1 << 3" - }, - "displayportMspCommand_e": { - "_source": "inav/src/main/io/displayport_msp.h", - "MSP_DP_HEARTBEAT": "0", - "MSP_DP_RELEASE": "1", - "MSP_DP_CLEAR_SCREEN": "2", - "MSP_DP_WRITE_STRING": "3", - "MSP_DP_DRAW_SCREEN": "4", - "MSP_DP_OPTIONS": "5", - "MSP_DP_SYS": "6", - "MSP_DP_COUNT": "7" - }, - "displayTransactionOption_e": { - "_source": "inav/src/main/drivers/display.h", - "DISPLAY_TRANSACTION_OPT_NONE": "0", - "DISPLAY_TRANSACTION_OPT_PROFILED": "1 << 0", - "DISPLAY_TRANSACTION_OPT_RESET_DRAWING": "1 << 1" - }, - "displayWidgetType_e": { - "_source": "inav/src/main/drivers/display_widgets.h", - "DISPLAY_WIDGET_TYPE_AHI": "0", - "DISPLAY_WIDGET_TYPE_SIDEBAR": "1" - }, - "DjiCraftNameElements_t": { - "_source": "inav/src/main/io/osd_dji_hd.c", - "DJI_OSD_CN_MESSAGES": "0", - "DJI_OSD_CN_THROTTLE": "1", - "DJI_OSD_CN_THROTTLE_AUTO_THR": "2", - "DJI_OSD_CN_AIR_SPEED": "3", - "DJI_OSD_CN_EFFICIENCY": "4", - "DJI_OSD_CN_DISTANCE": "5", - "DJI_OSD_CN_ADJUSTEMNTS": "6", - "DJI_OSD_CN_MAX_ELEMENTS": "7" - }, - "dshotCommands_e": { - "_source": "inav/src/main/drivers/pwm_output.h", - "DSHOT_CMD_SPIN_DIRECTION_NORMAL": "20", - "DSHOT_CMD_SPIN_DIRECTION_REVERSED": "21" - }, - "dumpFlags_e": { - "_source": "inav/src/main/fc/cli.c", - "DUMP_MASTER": "(1 << 0)", - "DUMP_CONTROL_PROFILE": "(1 << 1)", - "DUMP_BATTERY_PROFILE": "(1 << 2)", - "DUMP_MIXER_PROFILE": "(1 << 3)", - "DUMP_ALL": "(1 << 4)", - "DO_DIFF": "(1 << 5)", - "SHOW_DEFAULTS": "(1 << 6)", - "HIDE_UNUSED": "(1 << 7)" - }, - "dynamicGyroNotchMode_e": { - "_source": "inav/src/main/sensors/gyro.h", - "DYNAMIC_NOTCH_MODE_2D": "0", - "DYNAMIC_NOTCH_MODE_3D": "1" - }, - "emergLandState_e": { - "_source": "inav/src/main/flight/failsafe.h", - "EMERG_LAND_IDLE": "0", - "EMERG_LAND_IN_PROGRESS": "1", - "EMERG_LAND_HAS_LANDED": "2" - }, - "escSensorFrameStatus_t": { - "_source": "inav/src/main/sensors/esc_sensor.c", - "ESC_SENSOR_FRAME_PENDING": "0", - "ESC_SENSOR_FRAME_COMPLETE": "1", - "ESC_SENSOR_FRAME_FAILED": "2" - }, - "escSensorState_t": { - "_source": "inav/src/main/sensors/esc_sensor.c", - "ESC_SENSOR_WAIT_STARTUP": "0", - "ESC_SENSOR_READY": "1", - "ESC_SENSOR_WAITING": "2" - }, - "failsafeChannelBehavior_e": { - "_source": "inav/src/main/flight/failsafe.c", - "FAILSAFE_CHANNEL_HOLD": "0", - "FAILSAFE_CHANNEL_NEUTRAL": "1" - }, - "failsafePhase_e": { - "_source": "inav/src/main/flight/failsafe.h", - "FAILSAFE_IDLE": "0", - "FAILSAFE_RX_LOSS_DETECTED": "1", - "FAILSAFE_RX_LOSS_IDLE": "2", - "FAILSAFE_RETURN_TO_HOME": "3", - "FAILSAFE_LANDING": "4", - "FAILSAFE_LANDED": "5", - "FAILSAFE_RX_LOSS_MONITORING": "6", - "FAILSAFE_RX_LOSS_RECOVERED": "7" - }, - "failsafeProcedure_e": { - "_source": "inav/src/main/flight/failsafe.h", - "FAILSAFE_PROCEDURE_AUTO_LANDING": "0", - "FAILSAFE_PROCEDURE_DROP_IT": "1", - "FAILSAFE_PROCEDURE_RTH": "2", - "FAILSAFE_PROCEDURE_NONE": "3" - }, - "failsafeRxLinkState_e": { - "_source": "inav/src/main/flight/failsafe.h", - "FAILSAFE_RXLINK_DOWN": "0", - "FAILSAFE_RXLINK_UP": "1" - }, - "failureMode_e": { - "_source": "inav/src/main/drivers/system.h", - "FAILURE_DEVELOPER": "0", - "FAILURE_MISSING_ACC": "1", - "FAILURE_ACC_INIT": "2", - "FAILURE_ACC_INCOMPATIBLE": "3", - "FAILURE_INVALID_EEPROM_CONTENTS": "4", - "FAILURE_FLASH_WRITE_FAILED": "5", - "FAILURE_GYRO_INIT_FAILED": "6", - "FAILURE_FLASH_READ_FAILED": "7" - }, - "fatFilesystemType_e": { - "_source": "inav/src/main/io/asyncfatfs/fat_standard.h", - "FAT_FILESYSTEM_TYPE_INVALID": "0", - "FAT_FILESYSTEM_TYPE_FAT12": "1", - "FAT_FILESYSTEM_TYPE_FAT16": "2", - "FAT_FILESYSTEM_TYPE_FAT32": "3" - }, - "features_e": { - "_source": "inav/src/main/fc/config.h", - "FEATURE_THR_VBAT_COMP": "1 << 0", - "FEATURE_VBAT": "1 << 1", - "FEATURE_TX_PROF_SEL": "1 << 2", - "FEATURE_BAT_PROFILE_AUTOSWITCH": "1 << 3", - "FEATURE_GEOZONE": "1 << 4", - "FEATURE_UNUSED_1": "1 << 5", - "FEATURE_SOFTSERIAL": "1 << 6", - "FEATURE_GPS": "1 << 7", - "FEATURE_UNUSED_3": "1 << 8", - "FEATURE_UNUSED_4": "1 << 9", - "FEATURE_TELEMETRY": "1 << 10", - "FEATURE_CURRENT_METER": "1 << 11", - "FEATURE_REVERSIBLE_MOTORS": "1 << 12", - "FEATURE_UNUSED_5": "1 << 13", - "FEATURE_UNUSED_6": "1 << 14", - "FEATURE_RSSI_ADC": "1 << 15", - "FEATURE_LED_STRIP": "1 << 16", - "FEATURE_DASHBOARD": "1 << 17", - "FEATURE_UNUSED_7": "1 << 18", - "FEATURE_BLACKBOX": "1 << 19", - "FEATURE_UNUSED_10": "1 << 20", - "FEATURE_TRANSPONDER": "1 << 21", - "FEATURE_AIRMODE": "1 << 22", - "FEATURE_SUPEREXPO_RATES": "1 << 23", - "FEATURE_VTX": "1 << 24", - "FEATURE_UNUSED_8": "1 << 25", - "FEATURE_UNUSED_9": "1 << 26", - "FEATURE_UNUSED_11": "1 << 27", - "FEATURE_PWM_OUTPUT_ENABLE": "1 << 28", - "FEATURE_OSD": "1 << 29", - "FEATURE_FW_LAUNCH": "1 << 30", - "FEATURE_FW_AUTOTRIM": "1 << 31" - }, - "filterType_e": { - "_source": "inav/src/main/common/filter.h", - "FILTER_PT1": "0", - "FILTER_BIQUAD": "1", - "FILTER_PT2": "2", - "FILTER_PT3": "3", - "FILTER_LULU": "4" - }, - "fixedWingLaunchEvent_t": { - "_source": "inav/src/main/navigation/navigation_fw_launch.c", - "FW_LAUNCH_EVENT_NONE": "0", - "FW_LAUNCH_EVENT_SUCCESS": "1", - "FW_LAUNCH_EVENT_GOTO_DETECTION": "2", - "FW_LAUNCH_EVENT_ABORT": "3", - "FW_LAUNCH_EVENT_THROTTLE_LOW": "4", - "FW_LAUNCH_EVENT_COUNT": "5" - }, - "fixedWingLaunchMessage_t": { - "_source": "inav/src/main/navigation/navigation_fw_launch.c", - "FW_LAUNCH_MESSAGE_TYPE_NONE": "0", - "FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE": "1", - "FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE": "2", - "FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION": "3", - "FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS": "4", - "FW_LAUNCH_MESSAGE_TYPE_FINISHING": "5" - }, - "fixedWingLaunchState_t": { - "_source": "inav/src/main/navigation/navigation_fw_launch.c", - "FW_LAUNCH_STATE_WAIT_THROTTLE": "0", - "FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT": "1", - "FW_LAUNCH_STATE_IDLE_MOTOR_DELAY": "2", - "FW_LAUNCH_STATE_MOTOR_IDLE": "3", - "FW_LAUNCH_STATE_WAIT_DETECTION": "4", - "FW_LAUNCH_STATE_DETECTED": "5", - "FW_LAUNCH_STATE_MOTOR_DELAY": "6", - "FW_LAUNCH_STATE_MOTOR_SPINUP": "7", - "FW_LAUNCH_STATE_IN_PROGRESS": "8", - "FW_LAUNCH_STATE_FINISH": "9", - "FW_LAUNCH_STATE_ABORTED": "10", - "FW_LAUNCH_STATE_FLYING": "11", - "FW_LAUNCH_STATE_COUNT": "12" - }, - "flashPartitionType_e": { - "_source": "inav/src/main/drivers/flash.h", - "FLASH_PARTITION_TYPE_UNKNOWN": "0", - "FLASH_PARTITION_TYPE_PARTITION_TABLE": "1", - "FLASH_PARTITION_TYPE_FLASHFS": "2", - "FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT": "3", - "FLASH_PARTITION_TYPE_FIRMWARE": "4", - "FLASH_PARTITION_TYPE_CONFIG": "5", - "FLASH_PARTITION_TYPE_FULL_BACKUP": "6", - "FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META": "7", - "FLASH_PARTITION_TYPE_UPDATE_FIRMWARE": "8", - "FLASH_MAX_PARTITIONS": "9" - }, - "flashType_e": { - "_source": "inav/src/main/drivers/flash.h", - "FLASH_TYPE_NOR": "0", - "FLASH_TYPE_NAND": "1" - }, - "flight_dynamics_index_t": { - "_source": "inav/src/main/common/axis.h", - "FD_ROLL": "0", - "FD_PITCH": "1", - "FD_YAW": "2" - }, - "FlightLogEvent": { - "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", - "FLIGHT_LOG_EVENT_SYNC_BEEP": "0", - "FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT": "13", - "FLIGHT_LOG_EVENT_LOGGING_RESUME": "14", - "FLIGHT_LOG_EVENT_FLIGHTMODE": "30", - "FLIGHT_LOG_EVENT_IMU_FAILURE": "40", - "FLIGHT_LOG_EVENT_LOG_END": "255" - }, - "FlightLogFieldCondition": { - "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", - "FLIGHT_LOG_FIELD_CONDITION_ALWAYS": "0", - "FLIGHT_LOG_FIELD_CONDITION_MOTORS": "1", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1": "2", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2": "3", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3": "4", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4": "5", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5": "6", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6": "7", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7": "8", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8": "9", - "FLIGHT_LOG_FIELD_CONDITION_SERVOS": "10", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1": "11", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2": "12", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3": "13", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4": "14", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5": "15", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6": "16", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7": "17", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8": "18", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9": "19", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10": "20", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11": "21", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12": "22", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13": "23", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14": "24", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15": "25", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16": "26", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17": "27", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18": "28", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19": "29", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20": "30", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21": "31", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22": "32", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23": "33", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24": "34", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25": "35", - "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26": "36", - "FLIGHT_LOG_FIELD_CONDITION_MAG": "37", - "FLIGHT_LOG_FIELD_CONDITION_BARO": "38", - "FLIGHT_LOG_FIELD_CONDITION_PITOT": "39", - "FLIGHT_LOG_FIELD_CONDITION_VBAT": "40", - "FLIGHT_LOG_FIELD_CONDITION_AMPERAGE": "41", - "FLIGHT_LOG_FIELD_CONDITION_SURFACE": "42", - "FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV": "43", - "FLIGHT_LOG_FIELD_CONDITION_MC_NAV": "44", - "FLIGHT_LOG_FIELD_CONDITION_RSSI": "45", - "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0": "46", - "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1": "47", - "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2": "48", - "FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME": "49", - "FLIGHT_LOG_FIELD_CONDITION_DEBUG": "50", - "FLIGHT_LOG_FIELD_CONDITION_NAV_ACC": "51", - "FLIGHT_LOG_FIELD_CONDITION_NAV_POS": "52", - "FLIGHT_LOG_FIELD_CONDITION_NAV_PID": "53", - "FLIGHT_LOG_FIELD_CONDITION_ACC": "54", - "FLIGHT_LOG_FIELD_CONDITION_ATTITUDE": "55", - "FLIGHT_LOG_FIELD_CONDITION_RC_DATA": "56", - "FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND": "57", - "FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW": "58", - "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_ROLL": "59", - "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_PITCH": "60", - "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_YAW": "61", - "FLIGHT_LOG_FIELD_CONDITION_NEVER": "62", - "FLIGHT_LOG_FIELD_CONDITION_FIRST": "FLIGHT_LOG_FIELD_CONDITION_ALWAYS", - "FLIGHT_LOG_FIELD_CONDITION_LAST": "FLIGHT_LOG_FIELD_CONDITION_NEVER" - }, - "FlightLogFieldEncoding": { - "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", - "FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB": "0", - "FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB": "1", - "FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT": "3", - "FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB": "6", - "FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32": "7", - "FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16": "8", - "FLIGHT_LOG_FIELD_ENCODING_NULL": "9" - }, - "FlightLogFieldPredictor": { - "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", - "FLIGHT_LOG_FIELD_PREDICTOR_0": "0", - "FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS": "1", - "FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE": "2", - "FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2": "3", - "FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE": "4", - "FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0": "5", - "FLIGHT_LOG_FIELD_PREDICTOR_INC": "6", - "FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD": "7", - "FLIGHT_LOG_FIELD_PREDICTOR_1500": "8", - "FLIGHT_LOG_FIELD_PREDICTOR_VBATREF": "9", - "FLIGHT_LOG_FIELD_PREDICTOR_LAST_MAIN_FRAME_TIME": "10" - }, - "FlightLogFieldSign": { - "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", - "FLIGHT_LOG_FIELD_UNSIGNED": "0", - "FLIGHT_LOG_FIELD_SIGNED": "1" - }, - "flightModeFlags_e": { - "_source": "inav/src/main/fc/runtime_config.h", - "ANGLE_MODE": "(1 << 0)", - "HORIZON_MODE": "(1 << 1)", - "HEADING_MODE": "(1 << 2)", - "NAV_ALTHOLD_MODE": "(1 << 3)", - "NAV_RTH_MODE": "(1 << 4)", - "NAV_POSHOLD_MODE": "(1 << 5)", - "HEADFREE_MODE": "(1 << 6)", - "NAV_LAUNCH_MODE": "(1 << 7)", - "MANUAL_MODE": "(1 << 8)", - "FAILSAFE_MODE": "(1 << 9)", - "AUTO_TUNE": "(1 << 10)", - "NAV_WP_MODE": "(1 << 11)", - "NAV_COURSE_HOLD_MODE": "(1 << 12)", - "FLAPERON": "(1 << 13)", - "TURN_ASSISTANT": "(1 << 14)", - "TURTLE_MODE": "(1 << 15)", - "SOARING_MODE": "(1 << 16)", - "ANGLEHOLD_MODE": "(1 << 17)", - "NAV_FW_AUTOLAND": "(1 << 18)", - "NAV_SEND_TO": "(1 << 19)" - }, - "flightModeForTelemetry_e": { - "_source": "inav/src/main/fc/runtime_config.h", - "FLM_MANUAL": "0", - "FLM_ACRO": "1", - "FLM_ACRO_AIR": "2", - "FLM_ANGLE": "3", - "FLM_HORIZON": "4", - "FLM_ALTITUDE_HOLD": "5", - "FLM_POSITION_HOLD": "6", - "FLM_RTH": "7", - "FLM_MISSION": "8", - "FLM_COURSE_HOLD": "9", - "FLM_CRUISE": "10", - "FLM_LAUNCH": "11", - "FLM_FAILSAFE": "12", - "FLM_ANGLEHOLD": "13", - "FLM_COUNT": "14" - }, - "flyingPlatformType_e": { - "_source": "inav/src/main/flight/mixer.h", - "PLATFORM_MULTIROTOR": "0", - "PLATFORM_AIRPLANE": "1", - "PLATFORM_HELICOPTER": "2", - "PLATFORM_TRICOPTER": "3", - "PLATFORM_ROVER": "4", - "PLATFORM_BOAT": "5" - }, - "fport2_control_frame_type_e": { - "_source": "inav/src/main/rx/fport2.c", - "CFT_RC": "255", - "CFT_OTA_START": "240", - "CFT_OTA_DATA": "241", - "CFT_OTA_STOP": "242" - }, - "frame_state_e": { - "_source": "inav/src/main/rx/fport2.c", - "FS_CONTROL_FRAME_START": "0", - "FS_CONTROL_FRAME_TYPE": "1", - "FS_CONTROL_FRAME_DATA": "2", - "FS_DOWNLINK_FRAME_START": "3", - "FS_DOWNLINK_FRAME_DATA": "4" - }, - "frame_type_e": { - "_source": "inav/src/main/rx/fport2.c", - "FT_CONTROL": "0", - "FT_DOWNLINK": "1" - }, - "frskyOSDColor_e": { - "_source": "inav/src/main/io/frsky_osd.h", - "FRSKY_OSD_COLOR_BLACK": "0", - "FRSKY_OSD_COLOR_TRANSPARENT": "1", - "FRSKY_OSD_COLOR_WHITE": "2", - "FRSKY_OSD_COLOR_GRAY": "3" - }, - "frskyOSDLineOutlineType_e": { - "_source": "inav/src/main/io/frsky_osd.h", - "FRSKY_OSD_OUTLINE_TYPE_NONE": "0", - "FRSKY_OSD_OUTLINE_TYPE_TOP": "1 << 0", - "FRSKY_OSD_OUTLINE_TYPE_RIGHT": "1 << 1", - "FRSKY_OSD_OUTLINE_TYPE_BOTTOM": "1 << 2", - "FRSKY_OSD_OUTLINE_TYPE_LEFT": "1 << 3" - }, - "frskyOSDRecvState_e": { - "_source": "inav/src/main/io/frsky_osd.c", - "RECV_STATE_NONE": "0", - "RECV_STATE_SYNC": "1", - "RECV_STATE_LENGTH": "2", - "RECV_STATE_DATA": "3", - "RECV_STATE_CHECKSUM": "4", - "RECV_STATE_DONE": "5" - }, - "frskyOSDTransactionOptions_e": { - "_source": "inav/src/main/io/frsky_osd.h", - "FRSKY_OSD_TRANSACTION_OPT_PROFILED": "1 << 0", - "FRSKY_OSD_TRANSACTION_OPT_RESET_DRAWING": "1 << 1" - }, - "fw_autotune_rate_adjustment_e": { - "_source": "inav/src/main/flight/pid.h", - "FIXED": "0", - "LIMIT": "1", - "AUTO": "2" - }, - "fwAutolandApproachDirection_e": { - "_source": "inav/src/main/navigation/navigation.h", - "FW_AUTOLAND_APPROACH_DIRECTION_LEFT": "0", - "FW_AUTOLAND_APPROACH_DIRECTION_RIGHT": "1" - }, - "fwAutolandState_t": { - "_source": "inav/src/main/navigation/navigation.h", - "FW_AUTOLAND_STATE_IDLE": "0", - "FW_AUTOLAND_STATE_LOITER": "1", - "FW_AUTOLAND_STATE_DOWNWIND": "2", - "FW_AUTOLAND_STATE_BASE_LEG": "3", - "FW_AUTOLAND_STATE_FINAL_APPROACH": "4", - "FW_AUTOLAND_STATE_GLIDE": "5", - "FW_AUTOLAND_STATE_FLARE": "6" - }, - "fwAutolandWaypoint_t": { - "_source": "inav/src/main/navigation/navigation_private.h", - "FW_AUTOLAND_WP_TURN": "0", - "FW_AUTOLAND_WP_FINAL_APPROACH": "1", - "FW_AUTOLAND_WP_LAND": "2", - "FW_AUTOLAND_WP_COUNT": "3" - }, - "geoAltitudeConversionMode_e": { - "_source": "inav/src/main/navigation/navigation.h", - "GEO_ALT_ABSOLUTE": "0", - "GEO_ALT_RELATIVE": "1" - }, - "geoAltitudeDatumFlag_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_WP_TAKEOFF_DATUM": "0", - "NAV_WP_MSL_DATUM": "1" - }, - "geoOriginResetMode_e": { - "_source": "inav/src/main/navigation/navigation.h", - "GEO_ORIGIN_SET": "0", - "GEO_ORIGIN_RESET_ALTITUDE": "1" - }, - "geozoneActionState_e": { - "_source": "inav/src/main/navigation/navigation_geozone.c", - "GEOZONE_ACTION_STATE_NONE": "0", - "GEOZONE_ACTION_STATE_AVOIDING": "1", - "GEOZONE_ACTION_STATE_AVOIDING_UPWARD": "2", - "GEOZONE_ACTION_STATE_AVOIDING_ALTITUDE": "3", - "GEOZONE_ACTION_STATE_RETURN_TO_FZ": "4", - "GEOZONE_ACTION_STATE_FLYOUT_NFZ": "5", - "GEOZONE_ACTION_STATE_POSHOLD": "6", - "GEOZONE_ACTION_STATE_RTH": "7" - }, - "geozoneMessageState_e": { - "_source": "inav/src/main/navigation/navigation.h", - "GEOZONE_MESSAGE_STATE_NONE": "0", - "GEOZONE_MESSAGE_STATE_NFZ": "1", - "GEOZONE_MESSAGE_STATE_LEAVING_FZ": "2", - "GEOZONE_MESSAGE_STATE_OUTSIDE_FZ": "3", - "GEOZONE_MESSAGE_STATE_ENTERING_NFZ": "4", - "GEOZONE_MESSAGE_STATE_AVOIDING_FB": "5", - "GEOZONE_MESSAGE_STATE_RETURN_TO_ZONE": "6", - "GEOZONE_MESSAGE_STATE_FLYOUT_NFZ": "7", - "GEOZONE_MESSAGE_STATE_AVOIDING_ALTITUDE_BREACH": "8", - "GEOZONE_MESSAGE_STATE_POS_HOLD": "9" - }, - "ghstAddr_e": { - "_source": "inav/src/main/rx/ghst_protocol.h", - "GHST_ADDR_RADIO": "128", - "GHST_ADDR_TX_MODULE_SYM": "129", - "GHST_ADDR_TX_MODULE_ASYM": "136", - "GHST_ADDR_FC": "130", - "GHST_ADDR_GOGGLES": "131", - "GHST_ADDR_QUANTUM_TEE1": "132", - "GHST_ADDR_QUANTUM_TEE2": "133", - "GHST_ADDR_QUANTUM_GW1": "134", - "GHST_ADDR_5G_CLK": "135", - "GHST_ADDR_RX": "137" - }, - "ghstDl_e": { - "_source": "inav/src/main/rx/ghst_protocol.h", - "GHST_DL_OPENTX_SYNC": "32", - "GHST_DL_LINK_STAT": "33", - "GHST_DL_VTX_STAT": "34", - "GHST_DL_PACK_STAT": "35", - "GHST_DL_GPS_PRIMARY": "37", - "GHST_DL_GPS_SECONDARY": "38" - }, - "ghstFrameTypeIndex_e": { - "_source": "inav/src/main/telemetry/ghst.c", - "GHST_FRAME_START_INDEX": "0", - "GHST_FRAME_PACK_INDEX": "GHST_FRAME_START_INDEX", - "GHST_FRAME_GPS_PRIMARY_INDEX": "", - "GHST_FRAME_GPS_SECONDARY_INDEX": "", - "GHST_SCHEDULE_COUNT_MAX": "" - }, - "ghstUl_e": { - "_source": "inav/src/main/rx/ghst_protocol.h", - "GHST_UL_RC_CHANS_HS4_FIRST": "16", - "GHST_UL_RC_CHANS_HS4_5TO8": "16", - "GHST_UL_RC_CHANS_HS4_9TO12": "17", - "GHST_UL_RC_CHANS_HS4_13TO16": "18", - "GHST_UL_RC_CHANS_HS4_RSSI": "19", - "GHST_UL_RC_CHANS_HS4_LAST": "31" - }, - "gimbal_htk_mode_e": { - "_source": "inav/src/main/drivers/gimbal_common.h", - "GIMBAL_MODE_FOLLOW": "0", - "GIMBAL_MODE_TILT_LOCK": "(1<<0)", - "GIMBAL_MODE_ROLL_LOCK": "(1<<1)", - "GIMBAL_MODE_PAN_LOCK": "(1<<2)" - }, - "gimbalDevType_e": { - "_source": "inav/src/main/drivers/gimbal_common.h", - "GIMBAL_DEV_UNSUPPORTED": "0", - "GIMBAL_DEV_SERIAL": "1", - "GIMBAL_DEV_UNKNOWN": "255" - }, - "gimbalHeadtrackerState_e": { - "_source": "inav/src/main/io/gimbal_serial.h", - "WAITING_HDR1": "0", - "WAITING_HDR2": "1", - "WAITING_PAYLOAD": "2", - "WAITING_CRCH": "3", - "WAITING_CRCL": "4" - }, - "gpsAutoBaud_e": { - "_source": "inav/src/main/io/gps.h", - "GPS_AUTOBAUD_OFF": "0", - "GPS_AUTOBAUD_ON": "1" - }, - "gpsAutoConfig_e": { - "_source": "inav/src/main/io/gps.h", - "GPS_AUTOCONFIG_OFF": "0", - "GPS_AUTOCONFIG_ON": "1" - }, - "gpsBaudRate_e": { - "_source": "inav/src/main/io/gps.h", - "GPS_BAUDRATE_115200": "0", - "GPS_BAUDRATE_57600": "1", - "GPS_BAUDRATE_38400": "2", - "GPS_BAUDRATE_19200": "3", - "GPS_BAUDRATE_9600": "4", - "GPS_BAUDRATE_230400": "5", - "GPS_BAUDRATE_460800": "6", - "GPS_BAUDRATE_921600": "7", - "GPS_BAUDRATE_COUNT": "8" - }, - "gpsDynModel_e": { - "_source": "inav/src/main/io/gps.h", - "GPS_DYNMODEL_PEDESTRIAN": "0", - "GPS_DYNMODEL_AUTOMOTIVE": "1", - "GPS_DYNMODEL_AIR_1G": "2", - "GPS_DYNMODEL_AIR_2G": "3", - "GPS_DYNMODEL_AIR_4G": "4", - "GPS_DYNMODEL_SEA": "5", - "GPS_DYNMODEL_MOWER": "6" - }, - "gpsFixChar_e": { - "_source": "inav/src/main/telemetry/hott.c", - "GPS_FIX_CHAR_NONE": "'-'", - "GPS_FIX_CHAR_2D": "'2'", - "GPS_FIX_CHAR_3D": "'3'", - "GPS_FIX_CHAR_DGPS": "'D'" - }, - "gpsFixType_e": { - "_source": "inav/src/main/io/gps.h", - "GPS_NO_FIX": "0", - "GPS_FIX_2D": "1", - "GPS_FIX_3D": "2" - }, - "gpsProvider_e": { - "_source": "inav/src/main/io/gps.h", - "GPS_UBLOX": "0", - "GPS_MSP": "1", - "GPS_FAKE": "2", - "GPS_PROVIDER_COUNT": "3" - }, - "gpsState_e": { - "_source": "inav/src/main/io/gps_private.h", - "GPS_UNKNOWN": "0", - "GPS_INITIALIZING": "1", - "GPS_RUNNING": "2", - "GPS_LOST_COMMUNICATION": "3" - }, - "gyroFilterMode_e": { - "_source": "inav/src/main/sensors/gyro.h", - "GYRO_FILTER_MODE_OFF": "0", - "GYRO_FILTER_MODE_STATIC": "1", - "GYRO_FILTER_MODE_DYNAMIC": "2", - "GYRO_FILTER_MODE_ADAPTIVE": "3" - }, - "gyroHardwareLpf_e": { - "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", - "GYRO_HARDWARE_LPF_NORMAL": "0", - "GYRO_HARDWARE_LPF_OPTION_1": "1", - "GYRO_HARDWARE_LPF_OPTION_2": "2", - "GYRO_HARDWARE_LPF_EXPERIMENTAL": "3", - "GYRO_HARDWARE_LPF_COUNT": "4" - }, - "gyroSensor_e": { - "_source": "inav/src/main/sensors/gyro.h", - "GYRO_NONE": "0", - "GYRO_AUTODETECT": "1", - "GYRO_MPU6000": "2", - "GYRO_MPU6500": "3", - "GYRO_MPU9250": "4", - "GYRO_BMI160": "5", - "GYRO_ICM20689": "6", - "GYRO_BMI088": "7", - "GYRO_ICM42605": "8", - "GYRO_BMI270": "9", - "GYRO_LSM6DXX": "10", - "GYRO_FAKE": "11" - }, - "HardwareMotorTypes_e": { - "_source": "inav/src/main/drivers/pwm_esc_detect.h", - "MOTOR_UNKNOWN": "0", - "MOTOR_BRUSHED": "1", - "MOTOR_BRUSHLESS": "2" - }, - "hardwareSensorStatus_e": { - "_source": "inav/src/main/sensors/diagnostics.h", - "HW_SENSOR_NONE": "0", - "HW_SENSOR_OK": "1", - "HW_SENSOR_UNAVAILABLE": "2", - "HW_SENSOR_UNHEALTHY": "3" - }, - "headTrackerDevType_e": { - "_source": "inav/src/main/drivers/headtracker_common.h", - "HEADTRACKER_NONE": "0", - "HEADTRACKER_SERIAL": "1", - "HEADTRACKER_MSP": "2", - "HEADTRACKER_UNKNOWN": "255" - }, - "hottEamAlarm1Flag_e": { - "_source": "inav/src/main/telemetry/hott.h", - "HOTT_EAM_ALARM1_FLAG_NONE": "0", - "HOTT_EAM_ALARM1_FLAG_MAH": "(1 << 0)", - "HOTT_EAM_ALARM1_FLAG_BATTERY_1": "(1 << 1)", - "HOTT_EAM_ALARM1_FLAG_BATTERY_2": "(1 << 2)", - "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1": "(1 << 3)", - "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2": "(1 << 4)", - "HOTT_EAM_ALARM1_FLAG_ALTITUDE": "(1 << 5)", - "HOTT_EAM_ALARM1_FLAG_CURRENT": "(1 << 6)", - "HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE": "(1 << 7)" - }, - "hottEamAlarm2Flag_e": { - "_source": "inav/src/main/telemetry/hott.h", - "HOTT_EAM_ALARM2_FLAG_NONE": "0", - "HOTT_EAM_ALARM2_FLAG_MS": "(1 << 0)", - "HOTT_EAM_ALARM2_FLAG_M3S": "(1 << 1)", - "HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE": "(1 << 2)", - "HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE": "(1 << 3)", - "HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE": "(1 << 4)", - "HOTT_EAM_ALARM2_FLAG_UNKNOWN_1": "(1 << 5)", - "HOTT_EAM_ALARM2_FLAG_UNKNOWN_2": "(1 << 6)", - "HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE": "(1 << 7)" - }, - "hottState_e": { - "_source": "inav/src/main/telemetry/hott.c", - "HOTT_WAITING_FOR_REQUEST": "0", - "HOTT_RECEIVING_REQUEST": "1", - "HOTT_WAITING_FOR_TX_WINDOW": "2", - "HOTT_TRANSMITTING": "3", - "HOTT_ENDING_TRANSMISSION": "4" - }, - "hsvColorComponent_e": { - "_source": "inav/src/main/common/color.h", - "HSV_HUE": "0", - "HSV_SATURATION": "1", - "HSV_VALUE": "2" - }, - "I2CDevice": { - "_source": "inav/src/main/drivers/bus_i2c.h", - "I2CINVALID": "-1", - "I2CDEV_EMULATED": "-1", - "I2CDEV_1": "0", - "I2CDEV_2": "1", - "I2CDEV_3": "2", - "I2CDEV_4": [ - "(3)", - "USE_I2C_DEVICE_4" - ], - "I2CDEV_COUNT": "4" - }, - "I2CSpeed": { - "_source": "inav/src/main/drivers/bus_i2c.h", - "I2C_SPEED_100KHZ": "2", - "I2C_SPEED_200KHZ": "3", - "I2C_SPEED_400KHZ": "0", - "I2C_SPEED_800KHZ": "1" - }, - "i2cState_t": { - "_source": "inav/src/main/drivers/bus_i2c_stm32f40x.c", - "I2C_STATE_STOPPED": "0", - "I2C_STATE_STOPPING": "1", - "I2C_STATE_STARTING": "2", - "I2C_STATE_STARTING_WAIT": "3", - "I2C_STATE_R_ADDR": "4", - "I2C_STATE_R_ADDR_WAIT": "5", - "I2C_STATE_R_REGISTER": "6", - "I2C_STATE_R_REGISTER_WAIT": "7", - "I2C_STATE_R_RESTARTING": "8", - "I2C_STATE_R_RESTARTING_WAIT": "9", - "I2C_STATE_R_RESTART_ADDR": "10", - "I2C_STATE_R_RESTART_ADDR_WAIT": "11", - "I2C_STATE_R_TRANSFER_EQ1": "12", - "I2C_STATE_R_TRANSFER_EQ2": "13", - "I2C_STATE_R_TRANSFER_GE2": "14", - "I2C_STATE_W_ADDR": "15", - "I2C_STATE_W_ADDR_WAIT": "16", - "I2C_STATE_W_REGISTER": "17", - "I2C_STATE_W_TRANSFER_WAIT": "18", - "I2C_STATE_W_TRANSFER": "19", - "I2C_STATE_NACK": "20", - "I2C_STATE_BUS_ERROR": "21" - }, - "i2cTransferDirection_t": { - "_source": "inav/src/main/drivers/bus_i2c_stm32f40x.c", - "I2C_TXN_READ": "0", - "I2C_TXN_WRITE": "1" - }, - "ibusCommand_e": { - "_source": "inav/src/main/telemetry/ibus_shared.c", - "IBUS_COMMAND_DISCOVER_SENSOR": "128", - "IBUS_COMMAND_SENSOR_TYPE": "144", - "IBUS_COMMAND_MEASUREMENT": "160" - }, - "ibusSensorType1_e": { - "_source": "inav/src/main/telemetry/ibus_shared.h", - "IBUS_MEAS_TYPE1_INTV": "0", - "IBUS_MEAS_TYPE1_TEM": "1", - "IBUS_MEAS_TYPE1_MOT": "2", - "IBUS_MEAS_TYPE1_EXTV": "3", - "IBUS_MEAS_TYPE1_CELL": "4", - "IBUS_MEAS_TYPE1_BAT_CURR": "5", - "IBUS_MEAS_TYPE1_FUEL": "6", - "IBUS_MEAS_TYPE1_RPM": "7", - "IBUS_MEAS_TYPE1_CMP_HEAD": "8", - "IBUS_MEAS_TYPE1_CLIMB_RATE": "9", - "IBUS_MEAS_TYPE1_COG": "10", - "IBUS_MEAS_TYPE1_GPS_STATUS": "11", - "IBUS_MEAS_TYPE1_ACC_X": "12", - "IBUS_MEAS_TYPE1_ACC_Y": "13", - "IBUS_MEAS_TYPE1_ACC_Z": "14", - "IBUS_MEAS_TYPE1_ROLL": "15", - "IBUS_MEAS_TYPE1_PITCH": "16", - "IBUS_MEAS_TYPE1_YAW": "17", - "IBUS_MEAS_TYPE1_VERTICAL_SPEED": "18", - "IBUS_MEAS_TYPE1_GROUND_SPEED": "19", - "IBUS_MEAS_TYPE1_GPS_DIST": "20", - "IBUS_MEAS_TYPE1_ARMED": "21", - "IBUS_MEAS_TYPE1_FLIGHT_MODE": "22", - "IBUS_MEAS_TYPE1_PRES": "65", - "IBUS_MEAS_TYPE1_SPE": "126", - "IBUS_MEAS_TYPE1_GPS_LAT": "128", - "IBUS_MEAS_TYPE1_GPS_LON": "129", - "IBUS_MEAS_TYPE1_GPS_ALT": "130", - "IBUS_MEAS_TYPE1_ALT": "131", - "IBUS_MEAS_TYPE1_S84": "132", - "IBUS_MEAS_TYPE1_S85": "133", - "IBUS_MEAS_TYPE1_S86": "134", - "IBUS_MEAS_TYPE1_S87": "135", - "IBUS_MEAS_TYPE1_S88": "136", - "IBUS_MEAS_TYPE1_S89": "137", - "IBUS_MEAS_TYPE1_S8a": "138" - }, - "ibusSensorType_e": { - "_source": "inav/src/main/telemetry/ibus_shared.h", - "IBUS_MEAS_TYPE_INTERNAL_VOLTAGE": "0", - "IBUS_MEAS_TYPE_TEMPERATURE": "1", - "IBUS_MEAS_TYPE_RPM": "2", - "IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE": "3", - "IBUS_MEAS_TYPE_HEADING": "4", - "IBUS_MEAS_TYPE_CURRENT": "5", - "IBUS_MEAS_TYPE_CLIMB": "6", - "IBUS_MEAS_TYPE_ACC_Z": "7", - "IBUS_MEAS_TYPE_ACC_Y": "8", - "IBUS_MEAS_TYPE_ACC_X": "9", - "IBUS_MEAS_TYPE_VSPEED": "10", - "IBUS_MEAS_TYPE_SPEED": "11", - "IBUS_MEAS_TYPE_DIST": "12", - "IBUS_MEAS_TYPE_ARMED": "13", - "IBUS_MEAS_TYPE_MODE": "14", - "IBUS_MEAS_TYPE_PRES": "65", - "IBUS_MEAS_TYPE_SPE": "126", - "IBUS_MEAS_TYPE_COG": "128", - "IBUS_MEAS_TYPE_GPS_STATUS": "129", - "IBUS_MEAS_TYPE_GPS_LON": "130", - "IBUS_MEAS_TYPE_GPS_LAT": "131", - "IBUS_MEAS_TYPE_ALT": "132", - "IBUS_MEAS_TYPE_S85": "133", - "IBUS_MEAS_TYPE_S86": "134", - "IBUS_MEAS_TYPE_S87": "135", - "IBUS_MEAS_TYPE_S88": "136", - "IBUS_MEAS_TYPE_S89": "137", - "IBUS_MEAS_TYPE_S8A": "138", - "IBUS_MEAS_TYPE_GALT": "249", - "IBUS_MEAS_TYPE_GPS": "253" - }, - "ibusSensorValue_e": { - "_source": "inav/src/main/telemetry/ibus_shared.h", - "IBUS_MEAS_VALUE_NONE": "0", - "IBUS_MEAS_VALUE_TEMPERATURE": "1", - "IBUS_MEAS_VALUE_MOT": "2", - "IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE": "3", - "IBUS_MEAS_VALUE_CELL": "4", - "IBUS_MEAS_VALUE_CURRENT": "5", - "IBUS_MEAS_VALUE_FUEL": "6", - "IBUS_MEAS_VALUE_RPM": "7", - "IBUS_MEAS_VALUE_HEADING": "8", - "IBUS_MEAS_VALUE_CLIMB": "9", - "IBUS_MEAS_VALUE_COG": "10", - "IBUS_MEAS_VALUE_GPS_STATUS": "11", - "IBUS_MEAS_VALUE_ACC_X": "12", - "IBUS_MEAS_VALUE_ACC_Y": "13", - "IBUS_MEAS_VALUE_ACC_Z": "14", - "IBUS_MEAS_VALUE_ROLL": "15", - "IBUS_MEAS_VALUE_PITCH": "16", - "IBUS_MEAS_VALUE_YAW": "17", - "IBUS_MEAS_VALUE_VSPEED": "18", - "IBUS_MEAS_VALUE_SPEED": "19", - "IBUS_MEAS_VALUE_DIST": "20", - "IBUS_MEAS_VALUE_ARMED": "21", - "IBUS_MEAS_VALUE_MODE": "22", - "IBUS_MEAS_VALUE_PRES": "65", - "IBUS_MEAS_VALUE_SPE": "126", - "IBUS_MEAS_VALUE_GPS_LAT": "128", - "IBUS_MEAS_VALUE_GPS_LON": "129", - "IBUS_MEAS_VALUE_GALT4": "130", - "IBUS_MEAS_VALUE_ALT4": "131", - "IBUS_MEAS_VALUE_GALT": "132", - "IBUS_MEAS_VALUE_ALT": "133", - "IBUS_MEAS_VALUE_STATUS": "135", - "IBUS_MEAS_VALUE_GPS_LAT1": "136", - "IBUS_MEAS_VALUE_GPS_LON1": "137", - "IBUS_MEAS_VALUE_GPS_LAT2": "144", - "IBUS_MEAS_VALUE_GPS_LON2": "145", - "IBUS_MEAS_VALUE_GPS": "253" - }, - "inputSource_e": { - "_source": "inav/src/main/flight/servos.h", - "INPUT_STABILIZED_ROLL": "0", - "INPUT_STABILIZED_PITCH": "1", - "INPUT_STABILIZED_YAW": "2", - "INPUT_STABILIZED_THROTTLE": "3", - "INPUT_RC_ROLL": "4", - "INPUT_RC_PITCH": "5", - "INPUT_RC_YAW": "6", - "INPUT_RC_THROTTLE": "7", - "INPUT_RC_CH5": "8", - "INPUT_RC_CH6": "9", - "INPUT_RC_CH7": "10", - "INPUT_RC_CH8": "11", - "INPUT_GIMBAL_PITCH": "12", - "INPUT_GIMBAL_ROLL": "13", - "INPUT_FEATURE_FLAPS": "14", - "INPUT_RC_CH9": "15", - "INPUT_RC_CH10": "16", - "INPUT_RC_CH11": "17", - "INPUT_RC_CH12": "18", - "INPUT_RC_CH13": "19", - "INPUT_RC_CH14": "20", - "INPUT_RC_CH15": "21", - "INPUT_RC_CH16": "22", - "INPUT_STABILIZED_ROLL_PLUS": "23", - "INPUT_STABILIZED_ROLL_MINUS": "24", - "INPUT_STABILIZED_PITCH_PLUS": "25", - "INPUT_STABILIZED_PITCH_MINUS": "26", - "INPUT_STABILIZED_YAW_PLUS": "27", - "INPUT_STABILIZED_YAW_MINUS": "28", - "INPUT_MAX": "29", - "INPUT_GVAR_0": "30", - "INPUT_GVAR_1": "31", - "INPUT_GVAR_2": "32", - "INPUT_GVAR_3": "33", - "INPUT_GVAR_4": "34", - "INPUT_GVAR_5": "35", - "INPUT_GVAR_6": "36", - "INPUT_GVAR_7": "37", - "INPUT_MIXER_TRANSITION": "38", - "INPUT_HEADTRACKER_PAN": "39", - "INPUT_HEADTRACKER_TILT": "40", - "INPUT_HEADTRACKER_ROLL": "41", - "INPUT_RC_CH17": "42", - "INPUT_RC_CH18": "43", - "INPUT_RC_CH19": "44", - "INPUT_RC_CH20": "45", - "INPUT_RC_CH21": "46", - "INPUT_RC_CH22": "47", - "INPUT_RC_CH23": "48", - "INPUT_RC_CH24": "49", - "INPUT_RC_CH25": "50", - "INPUT_RC_CH26": "51", - "INPUT_RC_CH27": "52", - "INPUT_RC_CH28": "53", - "INPUT_RC_CH29": "54", - "INPUT_RC_CH30": "55", - "INPUT_RC_CH31": "56", - "INPUT_RC_CH32": "57", - "INPUT_RC_CH33": "58", - "INPUT_RC_CH34": "59", - "INPUT_MIXER_SWITCH_HELPER": "60", - "INPUT_SOURCE_COUNT": "61" - }, - "itermRelax_e": { - "_source": "inav/src/main/flight/pid.h", - "ITERM_RELAX_OFF": "0", - "ITERM_RELAX_RP": "1", - "ITERM_RELAX_RPY": "2" - }, - "led_pin_pwm_mode_e": { - "_source": "inav/src/main/drivers/light_ws2811strip.h", - "LED_PIN_PWM_MODE_SHARED_LOW": "0", - "LED_PIN_PWM_MODE_SHARED_HIGH": "1", - "LED_PIN_PWM_MODE_LOW": "2", - "LED_PIN_PWM_MODE_HIGH": "3" - }, - "ledBaseFunctionId_e": { - "_source": "inav/src/main/io/ledstrip.h", - "LED_FUNCTION_COLOR": "0", - "LED_FUNCTION_FLIGHT_MODE": "1", - "LED_FUNCTION_ARM_STATE": "2", - "LED_FUNCTION_BATTERY": "3", - "LED_FUNCTION_RSSI": "4", - "LED_FUNCTION_GPS": "5", - "LED_FUNCTION_THRUST_RING": "6", - "LED_FUNCTION_CHANNEL": "7" - }, - "ledDirectionId_e": { - "_source": "inav/src/main/io/ledstrip.h", - "LED_DIRECTION_NORTH": "0", - "LED_DIRECTION_EAST": "1", - "LED_DIRECTION_SOUTH": "2", - "LED_DIRECTION_WEST": "3", - "LED_DIRECTION_UP": "4", - "LED_DIRECTION_DOWN": "5" - }, - "ledModeIndex_e": { - "_source": "inav/src/main/io/ledstrip.h", - "LED_MODE_ORIENTATION": "0", - "LED_MODE_HEADFREE": "1", - "LED_MODE_HORIZON": "2", - "LED_MODE_ANGLE": "3", - "LED_MODE_MAG": "4", - "LED_MODE_BARO": "5", - "LED_SPECIAL": "6" - }, - "ledOverlayId_e": { - "_source": "inav/src/main/io/ledstrip.h", - "LED_OVERLAY_THROTTLE": "0", - "LED_OVERLAY_LARSON_SCANNER": "1", - "LED_OVERLAY_BLINK": "2", - "LED_OVERLAY_LANDING_FLASH": "3", - "LED_OVERLAY_INDICATOR": "4", - "LED_OVERLAY_WARNING": "5", - "LED_OVERLAY_STROBE": "6" - }, - "ledSpecialColorIds_e": { - "_source": "inav/src/main/io/ledstrip.h", - "LED_SCOLOR_DISARMED": "0", - "LED_SCOLOR_ARMED": "1", - "LED_SCOLOR_ANIMATION": "2", - "LED_SCOLOR_BACKGROUND": "3", - "LED_SCOLOR_BLINKBACKGROUND": "4", - "LED_SCOLOR_GPSNOSATS": "5", - "LED_SCOLOR_GPSNOLOCK": "6", - "LED_SCOLOR_GPSLOCKED": "7", - "LED_SCOLOR_STROBE": "8" - }, - "logicConditionFlags_e": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_FLAG_LATCH": "1 << 0", - "LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED": "1 << 1" - }, - "logicConditionsGlobalFlags_t": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY": "(1 << 0)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE": "(1 << 1)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW": "(1 << 2)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL": "(1 << 3)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH": "(1 << 4)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW": "(1 << 5)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE": "(1 << 6)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT": "(1 << 7)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL": "(1 << 8)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS": "(1 << 9)", - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_FLIGHT_AXIS": "(1 << 10)", - "LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX": [ - "(1 << 11)", - "USE_GPS_FIX_ESTIMATION" - ], - "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_MIN_GROUND_SPEED": "(1 << 12)" - }, - "logicFlightModeOperands_e": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_FAILSAFE": "0", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_MANUAL": "1", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_RTH": "2", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_POSHOLD": "3", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE": "4", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD": "5", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLE": "6", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_HORIZON": "7", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR": "8", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1": "9", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER2": "10", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD": "11", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3": "12", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4": "13", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO": "14", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION": "15", - "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD": "16" - }, - "logicFlightOperands_e": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER": "0", - "LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE": "1", - "LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE": "2", - "LOGIC_CONDITION_OPERAND_FLIGHT_RSSI": "3", - "LOGIC_CONDITION_OPERAND_FLIGHT_VBAT": "4", - "LOGIC_CONDITION_OPERAND_FLIGHT_CELL_VOLTAGE": "5", - "LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT": "6", - "LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN": "7", - "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_SATS": "8", - "LOGIC_CONDITION_OPERAND_FLIGHT_GROUD_SPEED": "9", - "LOGIC_CONDITION_OPERAND_FLIGHT_3D_SPEED": "10", - "LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED": "11", - "LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE": "12", - "LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED": "13", - "LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS": "14", - "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_ROLL": "15", - "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_PITCH": "16", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED": "17", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH": "18", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL": "19", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL": "20", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING": "21", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH": "22", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING": "23", - "LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE": "24", - "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL": "25", - "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH": "26", - "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW": "27", - "LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE": "28", - "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_UPLINK": "29", - "LOGIC_CONDITION_OPERAND_FLIGHT_SNR": "30", - "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID": "31", - "LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS": "32", - "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE": "33", - "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_CELLS": "34", - "LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS": "35", - "LOGIC_CONDITION_OPERAND_FLIGHT_AGL": "36", - "LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW": "37", - "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE": "38", - "LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE": "39", - "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW": "40", - "LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE": "41", - "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE": "42", - "LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS": "43", - "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK": "44", - "LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM": "45", - "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" - }, - "logicOperandType_e": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_OPERAND_TYPE_VALUE": "0", - "LOGIC_CONDITION_OPERAND_TYPE_RC_CHANNEL": "1", - "LOGIC_CONDITION_OPERAND_TYPE_FLIGHT": "2", - "LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE": "3", - "LOGIC_CONDITION_OPERAND_TYPE_LC": "4", - "LOGIC_CONDITION_OPERAND_TYPE_GVAR": "5", - "LOGIC_CONDITION_OPERAND_TYPE_PID": "6", - "LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS": "7", - "LOGIC_CONDITION_OPERAND_TYPE_LAST": "8" - }, - "logicOperation_e": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_TRUE": "0", - "LOGIC_CONDITION_EQUAL": "1", - "LOGIC_CONDITION_GREATER_THAN": "2", - "LOGIC_CONDITION_LOWER_THAN": "3", - "LOGIC_CONDITION_LOW": "4", - "LOGIC_CONDITION_MID": "5", - "LOGIC_CONDITION_HIGH": "6", - "LOGIC_CONDITION_AND": "7", - "LOGIC_CONDITION_OR": "8", - "LOGIC_CONDITION_XOR": "9", - "LOGIC_CONDITION_NAND": "10", - "LOGIC_CONDITION_NOR": "11", - "LOGIC_CONDITION_NOT": "12", - "LOGIC_CONDITION_STICKY": "13", - "LOGIC_CONDITION_ADD": "14", - "LOGIC_CONDITION_SUB": "15", - "LOGIC_CONDITION_MUL": "16", - "LOGIC_CONDITION_DIV": "17", - "LOGIC_CONDITION_GVAR_SET": "18", - "LOGIC_CONDITION_GVAR_INC": "19", - "LOGIC_CONDITION_GVAR_DEC": "20", - "LOGIC_CONDITION_PORT_SET": "21", - "LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY": "22", - "LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE": "23", - "LOGIC_CONDITION_SWAP_ROLL_YAW": "24", - "LOGIC_CONDITION_SET_VTX_POWER_LEVEL": "25", - "LOGIC_CONDITION_INVERT_ROLL": "26", - "LOGIC_CONDITION_INVERT_PITCH": "27", - "LOGIC_CONDITION_INVERT_YAW": "28", - "LOGIC_CONDITION_OVERRIDE_THROTTLE": "29", - "LOGIC_CONDITION_SET_VTX_BAND": "30", - "LOGIC_CONDITION_SET_VTX_CHANNEL": "31", - "LOGIC_CONDITION_SET_OSD_LAYOUT": "32", - "LOGIC_CONDITION_SIN": "33", - "LOGIC_CONDITION_COS": "34", - "LOGIC_CONDITION_TAN": "35", - "LOGIC_CONDITION_MAP_INPUT": "36", - "LOGIC_CONDITION_MAP_OUTPUT": "37", - "LOGIC_CONDITION_RC_CHANNEL_OVERRIDE": "38", - "LOGIC_CONDITION_SET_HEADING_TARGET": "39", - "LOGIC_CONDITION_MODULUS": "40", - "LOGIC_CONDITION_LOITER_OVERRIDE": "41", - "LOGIC_CONDITION_SET_PROFILE": "42", - "LOGIC_CONDITION_MIN": "43", - "LOGIC_CONDITION_MAX": "44", - "LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE": "45", - "LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE": "46", - "LOGIC_CONDITION_EDGE": "47", - "LOGIC_CONDITION_DELAY": "48", - "LOGIC_CONDITION_TIMER": "49", - "LOGIC_CONDITION_DELTA": "50", - "LOGIC_CONDITION_APPROX_EQUAL": "51", - "LOGIC_CONDITION_LED_PIN_PWM": "52", - "LOGIC_CONDITION_DISABLE_GPS_FIX": "53", - "LOGIC_CONDITION_RESET_MAG_CALIBRATION": "54", - "LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY": "55", - "LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED": "56", - "LOGIC_CONDITION_LAST": "57" - }, - "logicWaypointOperands_e": { - "_source": "inav/src/main/programming/logic_condition.h", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_IS_WP": "0", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_INDEX": "1", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_ACTION": "2", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_NEXT_WAYPOINT_ACTION": "3", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_DISTANCE": "4", - "LOGIC_CONDTIION_OPERAND_WAYPOINTS_DISTANCE_FROM_WAYPOINT": "5", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION": "6", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION": "7", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION": "8", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION": "9", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION_NEXT_WP": "10", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION_NEXT_WP": "11", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION_NEXT_WP": "12", - "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION_NEXT_WP": "13" - }, - "logTopic_e": { - "_source": "inav/src/main/common/log.h", - "LOG_TOPIC_SYSTEM": "0", - "LOG_TOPIC_GYRO": "1", - "LOG_TOPIC_BARO": "2", - "LOG_TOPIC_PITOT": "3", - "LOG_TOPIC_PWM": "4", - "LOG_TOPIC_TIMER": "5", - "LOG_TOPIC_IMU": "6", - "LOG_TOPIC_TEMPERATURE": "7", - "LOG_TOPIC_POS_ESTIMATOR": "8", - "LOG_TOPIC_VTX": "9", - "LOG_TOPIC_OSD": "10", - "LOG_TOPIC_COUNT": "11" - }, - "lsm6dxxConfigMasks_e": { - "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", - "LSM6DXX_MASK_COUNTER_BDR1": "128", - "LSM6DXX_MASK_CTRL3_C": "60", - "LSM6DXX_MASK_CTRL3_C_RESET": "BIT(0)", - "LSM6DXX_MASK_CTRL4_C": "14", - "LSM6DXX_MASK_CTRL6_C": "23", - "LSM6DXX_MASK_CTRL7_G": "112", - "LSM6DXX_MASK_CTRL9_XL": "2", - "LSM6DSL_MASK_CTRL6_C": "19" - }, - "lsm6dxxConfigValues_e": { - "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", - "LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM": "BIT(7)", - "LSM6DXX_VAL_INT1_CTRL": "2", - "LSM6DXX_VAL_INT2_CTRL": "0", - "LSM6DXX_VAL_CTRL1_XL_ODR833": "7", - "LSM6DXX_VAL_CTRL1_XL_ODR1667": "8", - "LSM6DXX_VAL_CTRL1_XL_ODR3332": "9", - "LSM6DXX_VAL_CTRL1_XL_ODR3333": "10", - "LSM6DXX_VAL_CTRL1_XL_8G": "3", - "LSM6DXX_VAL_CTRL1_XL_16G": "1", - "LSM6DXX_VAL_CTRL1_XL_LPF1": "0", - "LSM6DXX_VAL_CTRL1_XL_LPF2": "1", - "LSM6DXX_VAL_CTRL2_G_ODR6664": "10", - "LSM6DXX_VAL_CTRL2_G_2000DPS": "3", - "LSM6DXX_VAL_CTRL3_C_H_LACTIVE": "0", - "LSM6DXX_VAL_CTRL3_C_PP_OD": "0", - "LSM6DXX_VAL_CTRL3_C_SIM": "0", - "LSM6DXX_VAL_CTRL3_C_IF_INC": "BIT(2)", - "LSM6DXX_VAL_CTRL4_C_DRDY_MASK": "BIT(3)", - "LSM6DXX_VAL_CTRL4_C_I2C_DISABLE": "BIT(2)", - "LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G": "BIT(1)", - "LSM6DXX_VAL_CTRL6_C_XL_HM_MODE": "0", - "LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ": "0", - "LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ": "1", - "LSM6DXX_VAL_CTRL6_C_FTYPE_102HZ": "2", - "LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ": "3", - "LSM6DXX_VAL_CTRL7_G_HP_EN_G": "BIT(6)", - "LSM6DXX_VAL_CTRL7_G_HPM_G_16": "0", - "LSM6DXX_VAL_CTRL7_G_HPM_G_65": "1", - "LSM6DXX_VAL_CTRL7_G_HPM_G_260": "2", - "LSM6DXX_VAL_CTRL7_G_HPM_G_1040": "3", - "LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE": "BIT(1)" - }, - "lsm6dxxRegister_e": { - "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", - "LSM6DXX_REG_COUNTER_BDR1": "11", - "LSM6DXX_REG_INT1_CTRL": "13", - "LSM6DXX_REG_INT2_CTRL": "14", - "LSM6DXX_REG_WHO_AM_I": "15", - "LSM6DXX_REG_CTRL1_XL": "16", - "LSM6DXX_REG_CTRL2_G": "17", - "LSM6DXX_REG_CTRL3_C": "18", - "LSM6DXX_REG_CTRL4_C": "19", - "LSM6DXX_REG_CTRL5_C": "20", - "LSM6DXX_REG_CTRL6_C": "21", - "LSM6DXX_REG_CTRL7_G": "22", - "LSM6DXX_REG_CTRL8_XL": "23", - "LSM6DXX_REG_CTRL9_XL": "24", - "LSM6DXX_REG_CTRL10_C": "25", - "LSM6DXX_REG_STATUS": "30", - "LSM6DXX_REG_OUT_TEMP_L": "32", - "LSM6DXX_REG_OUT_TEMP_H": "33", - "LSM6DXX_REG_OUTX_L_G": "34", - "LSM6DXX_REG_OUTX_H_G": "35", - "LSM6DXX_REG_OUTY_L_G": "36", - "LSM6DXX_REG_OUTY_H_G": "37", - "LSM6DXX_REG_OUTZ_L_G": "38", - "LSM6DXX_REG_OUTZ_H_G": "39", - "LSM6DXX_REG_OUTX_L_A": "40", - "LSM6DXX_REG_OUTX_H_A": "41", - "LSM6DXX_REG_OUTY_L_A": "42", - "LSM6DXX_REG_OUTY_H_A": "43", - "LSM6DXX_REG_OUTZ_L_A": "44", - "LSM6DXX_REG_OUTZ_H_A": "45" - }, - "ltm_frame_e": { - "_source": "inav/src/main/telemetry/ltm.h", - "LTM_FRAME_START": "0", - "LTM_AFRAME": "LTM_FRAME_START", - "LTM_SFRAME": "", - "LTM_GFRAME": [ - "", - "USE_GPS" - ], - "LTM_OFRAME": [ - "", - "USE_GPS" - ], - "LTM_XFRAME": [ - "", - "USE_GPS" - ], - "LTM_NFRAME": "", - "LTM_FRAME_COUNT": "" - }, - "ltm_modes_e": { - "_source": "inav/src/main/telemetry/ltm.h", - "LTM_MODE_MANUAL": "0", - "LTM_MODE_RATE": "1", - "LTM_MODE_ANGLE": "2", - "LTM_MODE_HORIZON": "3", - "LTM_MODE_ACRO": "4", - "LTM_MODE_STABALIZED1": "5", - "LTM_MODE_STABALIZED2": "6", - "LTM_MODE_STABILIZED3": "7", - "LTM_MODE_ALTHOLD": "8", - "LTM_MODE_GPSHOLD": "9", - "LTM_MODE_WAYPOINTS": "10", - "LTM_MODE_HEADHOLD": "11", - "LTM_MODE_CIRCLE": "12", - "LTM_MODE_RTH": "13", - "LTM_MODE_FOLLOWWME": "14", - "LTM_MODE_LAND": "15", - "LTM_MODE_FLYBYWIRE1": "16", - "LTM_MODE_FLYBYWIRE2": "17", - "LTM_MODE_CRUISE": "18", - "LTM_MODE_UNKNOWN": "19", - "LTM_MODE_LAUNCH": "20", - "LTM_MODE_AUTOTUNE": "21" - }, - "ltmUpdateRate_e": { - "_source": "inav/src/main/telemetry/telemetry.h", - "LTM_RATE_NORMAL": "0", - "LTM_RATE_MEDIUM": "1", - "LTM_RATE_SLOW": "2" - }, - "magSensor_e": { - "_source": "inav/src/main/sensors/compass.h", - "MAG_NONE": "0", - "MAG_AUTODETECT": "1", - "MAG_HMC5883": "2", - "MAG_AK8975": "3", - "MAG_MAG3110": "4", - "MAG_AK8963": "5", - "MAG_IST8310": "6", - "MAG_QMC5883": "7", - "MAG_QMC5883P": "8", - "MAG_MPU9250": "9", - "MAG_IST8308": "10", - "MAG_LIS3MDL": "11", - "MAG_MSP": "12", - "MAG_RM3100": "13", - "MAG_VCM5883": "14", - "MAG_MLX90393": "15", - "MAG_FAKE": "16", - "MAG_MAX": "MAG_FAKE" - }, - "mavlinkAutopilotType_e": { - "_source": "inav/src/main/telemetry/telemetry.h", - "MAVLINK_AUTOPILOT_GENERIC": "0", - "MAVLINK_AUTOPILOT_ARDUPILOT": "1" - }, - "mavlinkRadio_e": { - "_source": "inav/src/main/telemetry/telemetry.h", - "MAVLINK_RADIO_GENERIC": "0", - "MAVLINK_RADIO_ELRS": "1", - "MAVLINK_RADIO_SIK": "2" - }, - "measurementSteps_e": { - "_source": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c", - "MEASUREMENT_START": "0", - "MEASUREMENT_WAIT": "1", - "MEASUREMENT_READ": "2" - }, - "mixerProfileATRequest_e": { - "_source": "inav/src/main/flight/mixer_profile.h", - "MIXERAT_REQUEST_NONE": "0", - "MIXERAT_REQUEST_RTH": "1", - "MIXERAT_REQUEST_LAND": "2", - "MIXERAT_REQUEST_ABORT": "3" - }, - "mixerProfileATState_e": { - "_source": "inav/src/main/flight/mixer_profile.h", - "MIXERAT_PHASE_IDLE": "0", - "MIXERAT_PHASE_TRANSITION_INITIALIZE": "1", - "MIXERAT_PHASE_TRANSITIONING": "2", - "MIXERAT_PHASE_DONE": "3" - }, - "modeActivationOperator_e": { - "_source": "inav/src/main/fc/rc_modes.h", - "MODE_OPERATOR_OR": "0", - "MODE_OPERATOR_AND": "1" - }, - "motorPwmProtocolTypes_e": { - "_source": "inav/src/main/drivers/pwm_mapping.h", - "PWM_TYPE_STANDARD": "0", - "PWM_TYPE_ONESHOT125": "1", - "PWM_TYPE_MULTISHOT": "2", - "PWM_TYPE_BRUSHED": "3", - "PWM_TYPE_DSHOT150": "4", - "PWM_TYPE_DSHOT300": "5", - "PWM_TYPE_DSHOT600": "6" - }, - "motorStatus_e": { - "_source": "inav/src/main/flight/mixer.h", - "MOTOR_STOPPED_USER": "0", - "MOTOR_STOPPED_AUTO": "1", - "MOTOR_RUNNING": "2" - }, - "mpu9250CompassReadState_e": { - "_source": "inav/src/main/drivers/compass/compass_mpu9250.c", - "CHECK_STATUS": "0", - "WAITING_FOR_STATUS": "1", - "WAITING_FOR_DATA": "2" - }, - "mspFlashfsFlags_e": { - "_source": "inav/src/main/fc/fc_msp.c", - "MSP_FLASHFS_BIT_READY": "1", - "MSP_FLASHFS_BIT_SUPPORTED": "2" - }, - "mspPassthroughType_e": { - "_source": "inav/src/main/fc/fc_msp.c", - "MSP_PASSTHROUGH_SERIAL_ID": "253", - "MSP_PASSTHROUGH_SERIAL_FUNCTION_ID": "254", - "MSP_PASSTHROUGH_ESC_4WAY": "255" - }, - "mspSDCardFlags_e": { - "_source": "inav/src/main/fc/fc_msp.c", - "MSP_SDCARD_FLAG_SUPPORTTED": "1" - }, - "mspSDCardState_e": { - "_source": "inav/src/main/fc/fc_msp.c", - "MSP_SDCARD_STATE_NOT_PRESENT": "0", - "MSP_SDCARD_STATE_FATAL": "1", - "MSP_SDCARD_STATE_CARD_INIT": "2", - "MSP_SDCARD_STATE_FS_INIT": "3", - "MSP_SDCARD_STATE_READY": "4" - }, - "multi_function_e": { - "_source": "inav/src/main/fc/multifunction.h", - "MULTI_FUNC_NONE": "0", - "MULTI_FUNC_1": "1", - "MULTI_FUNC_2": "2", - "MULTI_FUNC_3": "3", - "MULTI_FUNC_4": "4", - "MULTI_FUNC_5": "5", - "MULTI_FUNC_6": "6", - "MULTI_FUNC_END": "7" - }, - "multiFunctionFlags_e": { - "_source": "inav/src/main/fc/multifunction.h", - "MF_SUSPEND_SAFEHOMES": "(1 << 0)", - "MF_SUSPEND_TRACKBACK": "(1 << 1)", - "MF_TURTLE_MODE": "(1 << 2)" - }, - "nav_reset_type_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_RESET_NEVER": "0", - "NAV_RESET_ON_FIRST_ARM": "1", - "NAV_RESET_ON_EACH_ARM": "2" - }, - "navAGLEstimateQuality_e": { - "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h", - "SURFACE_QUAL_LOW": "0", - "SURFACE_QUAL_MID": "1", - "SURFACE_QUAL_HIGH": "2" - }, - "navArmingBlocker_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_ARMING_BLOCKER_NONE": "0", - "NAV_ARMING_BLOCKER_MISSING_GPS_FIX": "1", - "NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE": "2", - "NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR": "3", - "NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR": "4" - }, - "navDefaultAltitudeSensor_e": { - "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h", - "ALTITUDE_SOURCE_GPS": "0", - "ALTITUDE_SOURCE_BARO": "1", - "ALTITUDE_SOURCE_GPS_ONLY": "2", - "ALTITUDE_SOURCE_BARO_ONLY": "3" - }, - "navExtraArmingSafety_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_EXTRA_ARMING_SAFETY_ON": "0", - "NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS": "1" - }, - "navFwLaunchStatus_e": { - "_source": "inav/src/main/navigation/navigation.h", - "FW_LAUNCH_DETECTED": "5", - "FW_LAUNCH_ABORTED": "10", - "FW_LAUNCH_FLYING": "11" - }, - "navigationEstimateStatus_e": { - "_source": "inav/src/main/navigation/navigation_private.h", - "EST_NONE": "0", - "EST_USABLE": "1", - "EST_TRUSTED": "2" - }, - "navigationFSMEvent_t": { - "_source": "inav/src/main/navigation/navigation_private.h", - "NAV_FSM_EVENT_NONE": "0", - "NAV_FSM_EVENT_TIMEOUT": "1", - "NAV_FSM_EVENT_SUCCESS": "2", - "NAV_FSM_EVENT_ERROR": "3", - "NAV_FSM_EVENT_SWITCH_TO_IDLE": "4", - "NAV_FSM_EVENT_SWITCH_TO_ALTHOLD": "5", - "NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D": "6", - "NAV_FSM_EVENT_SWITCH_TO_RTH": "7", - "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT": "8", - "NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING": "9", - "NAV_FSM_EVENT_SWITCH_TO_LAUNCH": "10", - "NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD": "11", - "NAV_FSM_EVENT_SWITCH_TO_CRUISE": "12", - "NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ": "13", - "NAV_FSM_EVENT_SWITCH_TO_MIXERAT": "14", - "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING": "15", - "NAV_FSM_EVENT_SWITCH_TO_SEND_TO": "16", - "NAV_FSM_EVENT_STATE_SPECIFIC_1": "17", - "NAV_FSM_EVENT_STATE_SPECIFIC_2": "18", - "NAV_FSM_EVENT_STATE_SPECIFIC_3": "19", - "NAV_FSM_EVENT_STATE_SPECIFIC_4": "20", - "NAV_FSM_EVENT_STATE_SPECIFIC_5": "21", - "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_ABORT": "NAV_FSM_EVENT_STATE_SPECIFIC_1", - "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_2", - "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_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", - "NAV_FSM_EVENT_SWITCH_TO_RTH_LOITER_ABOVE_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_4", - "NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING": "NAV_FSM_EVENT_STATE_SPECIFIC_5", - "NAV_FSM_EVENT_COUNT": "" - }, - "navigationFSMState_t": { - "_source": "inav/src/main/navigation/navigation_private.h", - "NAV_STATE_UNDEFINED": "0", - "NAV_STATE_IDLE": "1", - "NAV_STATE_ALTHOLD_INITIALIZE": "2", - "NAV_STATE_ALTHOLD_IN_PROGRESS": "3", - "NAV_STATE_POSHOLD_3D_INITIALIZE": "4", - "NAV_STATE_POSHOLD_3D_IN_PROGRESS": "5", - "NAV_STATE_RTH_INITIALIZE": "6", - "NAV_STATE_RTH_CLIMB_TO_SAFE_ALT": "7", - "NAV_STATE_RTH_TRACKBACK": "8", - "NAV_STATE_RTH_HEAD_HOME": "9", - "NAV_STATE_RTH_LOITER_PRIOR_TO_LANDING": "10", - "NAV_STATE_RTH_LOITER_ABOVE_HOME": "11", - "NAV_STATE_RTH_LANDING": "12", - "NAV_STATE_RTH_FINISHING": "13", - "NAV_STATE_RTH_FINISHED": "14", - "NAV_STATE_WAYPOINT_INITIALIZE": "15", - "NAV_STATE_WAYPOINT_PRE_ACTION": "16", - "NAV_STATE_WAYPOINT_IN_PROGRESS": "17", - "NAV_STATE_WAYPOINT_REACHED": "18", - "NAV_STATE_WAYPOINT_HOLD_TIME": "19", - "NAV_STATE_WAYPOINT_NEXT": "20", - "NAV_STATE_WAYPOINT_FINISHED": "21", - "NAV_STATE_WAYPOINT_RTH_LAND": "22", - "NAV_STATE_EMERGENCY_LANDING_INITIALIZE": "23", - "NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS": "24", - "NAV_STATE_EMERGENCY_LANDING_FINISHED": "25", - "NAV_STATE_LAUNCH_INITIALIZE": "26", - "NAV_STATE_LAUNCH_WAIT": "27", - "NAV_STATE_LAUNCH_IN_PROGRESS": "28", - "NAV_STATE_COURSE_HOLD_INITIALIZE": "29", - "NAV_STATE_COURSE_HOLD_IN_PROGRESS": "30", - "NAV_STATE_COURSE_HOLD_ADJUSTING": "31", - "NAV_STATE_CRUISE_INITIALIZE": "32", - "NAV_STATE_CRUISE_IN_PROGRESS": "33", - "NAV_STATE_CRUISE_ADJUSTING": "34", - "NAV_STATE_FW_LANDING_CLIMB_TO_LOITER": "35", - "NAV_STATE_FW_LANDING_LOITER": "36", - "NAV_STATE_FW_LANDING_APPROACH": "37", - "NAV_STATE_FW_LANDING_GLIDE": "38", - "NAV_STATE_FW_LANDING_FLARE": "39", - "NAV_STATE_FW_LANDING_FINISHED": "40", - "NAV_STATE_FW_LANDING_ABORT": "41", - "NAV_STATE_MIXERAT_INITIALIZE": "42", - "NAV_STATE_MIXERAT_IN_PROGRESS": "43", - "NAV_STATE_MIXERAT_ABORT": "44", - "NAV_STATE_SEND_TO_INITALIZE": "45", - "NAV_STATE_SEND_TO_IN_PROGESS": "46", - "NAV_STATE_SEND_TO_FINISHED": "47", - "NAV_STATE_COUNT": "48" - }, - "navigationFSMStateFlags_t": { - "_source": "inav/src/main/navigation/navigation_private.h", - "NAV_CTL_ALT": "(1 << 0)", - "NAV_CTL_POS": "(1 << 1)", - "NAV_CTL_YAW": "(1 << 2)", - "NAV_CTL_EMERG": "(1 << 3)", - "NAV_CTL_LAUNCH": "(1 << 4)", - "NAV_REQUIRE_ANGLE": "(1 << 5)", - "NAV_REQUIRE_ANGLE_FW": "(1 << 6)", - "NAV_REQUIRE_MAGHOLD": "(1 << 7)", - "NAV_REQUIRE_THRTILT": "(1 << 8)", - "NAV_AUTO_RTH": "(1 << 9)", - "NAV_AUTO_WP": "(1 << 10)", - "NAV_RC_ALT": "(1 << 11)", - "NAV_RC_POS": "(1 << 12)", - "NAV_RC_YAW": "(1 << 13)", - "NAV_CTL_LAND": "(1 << 14)", - "NAV_AUTO_WP_DONE": "(1 << 15)", - "NAV_MIXERAT": "(1 << 16)", - "NAV_CTL_HOLD": "(1 << 17)" - }, - "navigationHomeFlags_t": { - "_source": "inav/src/main/navigation/navigation_private.h", - "NAV_HOME_INVALID": "0", - "NAV_HOME_VALID_XY": "1 << 0", - "NAV_HOME_VALID_Z": "1 << 1", - "NAV_HOME_VALID_HEADING": "1 << 2", - "NAV_HOME_VALID_ALL": "NAV_HOME_VALID_XY | NAV_HOME_VALID_Z | NAV_HOME_VALID_HEADING" - }, - "navigationPersistentId_e": { - "_source": "inav/src/main/navigation/navigation_private.h", - "NAV_PERSISTENT_ID_UNDEFINED": "0", - "NAV_PERSISTENT_ID_IDLE": "1", - "NAV_PERSISTENT_ID_ALTHOLD_INITIALIZE": "2", - "NAV_PERSISTENT_ID_ALTHOLD_IN_PROGRESS": "3", - "NAV_PERSISTENT_ID_UNUSED_1": "4", - "NAV_PERSISTENT_ID_UNUSED_2": "5", - "NAV_PERSISTENT_ID_POSHOLD_3D_INITIALIZE": "6", - "NAV_PERSISTENT_ID_POSHOLD_3D_IN_PROGRESS": "7", - "NAV_PERSISTENT_ID_RTH_INITIALIZE": "8", - "NAV_PERSISTENT_ID_RTH_CLIMB_TO_SAFE_ALT": "9", - "NAV_PERSISTENT_ID_RTH_HEAD_HOME": "10", - "NAV_PERSISTENT_ID_RTH_LOITER_PRIOR_TO_LANDING": "11", - "NAV_PERSISTENT_ID_RTH_LANDING": "12", - "NAV_PERSISTENT_ID_RTH_FINISHING": "13", - "NAV_PERSISTENT_ID_RTH_FINISHED": "14", - "NAV_PERSISTENT_ID_WAYPOINT_INITIALIZE": "15", - "NAV_PERSISTENT_ID_WAYPOINT_PRE_ACTION": "16", - "NAV_PERSISTENT_ID_WAYPOINT_IN_PROGRESS": "17", - "NAV_PERSISTENT_ID_WAYPOINT_REACHED": "18", - "NAV_PERSISTENT_ID_WAYPOINT_NEXT": "19", - "NAV_PERSISTENT_ID_WAYPOINT_FINISHED": "20", - "NAV_PERSISTENT_ID_WAYPOINT_RTH_LAND": "21", - "NAV_PERSISTENT_ID_EMERGENCY_LANDING_INITIALIZE": "22", - "NAV_PERSISTENT_ID_EMERGENCY_LANDING_IN_PROGRESS": "23", - "NAV_PERSISTENT_ID_EMERGENCY_LANDING_FINISHED": "24", - "NAV_PERSISTENT_ID_LAUNCH_INITIALIZE": "25", - "NAV_PERSISTENT_ID_LAUNCH_WAIT": "26", - "NAV_PERSISTENT_ID_UNUSED_3": "27", - "NAV_PERSISTENT_ID_LAUNCH_IN_PROGRESS": "28", - "NAV_PERSISTENT_ID_COURSE_HOLD_INITIALIZE": "29", - "NAV_PERSISTENT_ID_COURSE_HOLD_IN_PROGRESS": "30", - "NAV_PERSISTENT_ID_COURSE_HOLD_ADJUSTING": "31", - "NAV_PERSISTENT_ID_CRUISE_INITIALIZE": "32", - "NAV_PERSISTENT_ID_CRUISE_IN_PROGRESS": "33", - "NAV_PERSISTENT_ID_CRUISE_ADJUSTING": "34", - "NAV_PERSISTENT_ID_WAYPOINT_HOLD_TIME": "35", - "NAV_PERSISTENT_ID_RTH_LOITER_ABOVE_HOME": "36", - "NAV_PERSISTENT_ID_UNUSED_4": "37", - "NAV_PERSISTENT_ID_RTH_TRACKBACK": "38", - "NAV_PERSISTENT_ID_MIXERAT_INITIALIZE": "39", - "NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS": "40", - "NAV_PERSISTENT_ID_MIXERAT_ABORT": "41", - "NAV_PERSISTENT_ID_FW_LANDING_CLIMB_TO_LOITER": "42", - "NAV_PERSISTENT_ID_FW_LANDING_LOITER": "43", - "NAV_PERSISTENT_ID_FW_LANDING_APPROACH": "44", - "NAV_PERSISTENT_ID_FW_LANDING_GLIDE": "45", - "NAV_PERSISTENT_ID_FW_LANDING_FLARE": "46", - "NAV_PERSISTENT_ID_FW_LANDING_ABORT": "47", - "NAV_PERSISTENT_ID_FW_LANDING_FINISHED": "48", - "NAV_PERSISTENT_ID_SEND_TO_INITALIZE": "49", - "NAV_PERSISTENT_ID_SEND_TO_IN_PROGRES": "50", - "NAV_PERSISTENT_ID_SEND_TO_FINISHED": "51" - }, - "navMcAltHoldThrottle_e": { - "_source": "inav/src/main/navigation/navigation.h", - "MC_ALT_HOLD_STICK": "0", - "MC_ALT_HOLD_MID": "1", - "MC_ALT_HOLD_HOVER": "2" - }, - "navMissionRestart_e": { - "_source": "inav/src/main/navigation/navigation.h", - "WP_MISSION_START": "0", - "WP_MISSION_RESUME": "1", - "WP_MISSION_SWITCH": "2" - }, - "navOverridesMotorStop_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NOMS_OFF_ALWAYS": "0", - "NOMS_OFF": "1", - "NOMS_AUTO_ONLY": "2", - "NOMS_ALL_NAV": "3" - }, - "navPositionEstimationFlags_e": { - "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h", - "EST_GPS_XY_VALID": "(1 << 0)", - "EST_GPS_Z_VALID": "(1 << 1)", - "EST_BARO_VALID": "(1 << 2)", - "EST_SURFACE_VALID": "(1 << 3)", - "EST_FLOW_VALID": "(1 << 4)", - "EST_XY_VALID": "(1 << 5)", - "EST_Z_VALID": "(1 << 6)" - }, - "navRTHAllowLanding_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_RTH_ALLOW_LANDING_NEVER": "0", - "NAV_RTH_ALLOW_LANDING_ALWAYS": "1", - "NAV_RTH_ALLOW_LANDING_FS_ONLY": "2" - }, - "navRTHClimbFirst_e": { - "_source": "inav/src/main/navigation/navigation.h", - "RTH_CLIMB_OFF": "0", - "RTH_CLIMB_ON": "1", - "RTH_CLIMB_ON_FW_SPIRAL": "2" - }, - "navSetWaypointFlags_t": { - "_source": "inav/src/main/navigation/navigation_private.h", - "NAV_POS_UPDATE_NONE": "0", - "NAV_POS_UPDATE_Z": "1 << 1", - "NAV_POS_UPDATE_XY": "1 << 0", - "NAV_POS_UPDATE_HEADING": "1 << 2", - "NAV_POS_UPDATE_BEARING": "1 << 3", - "NAV_POS_UPDATE_BEARING_TAIL_FIRST": "1 << 4" - }, - "navSystemStatus_Error_e": { - "_source": "inav/src/main/navigation/navigation.h", - "MW_NAV_ERROR_NONE": "0", - "MW_NAV_ERROR_TOOFAR": "1", - "MW_NAV_ERROR_SPOILED_GPS": "2", - "MW_NAV_ERROR_WP_CRC": "3", - "MW_NAV_ERROR_FINISH": "4", - "MW_NAV_ERROR_TIMEWAIT": "5", - "MW_NAV_ERROR_INVALID_JUMP": "6", - "MW_NAV_ERROR_INVALID_DATA": "7", - "MW_NAV_ERROR_WAIT_FOR_RTH_ALT": "8", - "MW_NAV_ERROR_GPS_FIX_LOST": "9", - "MW_NAV_ERROR_DISARMED": "10", - "MW_NAV_ERROR_LANDING": "11" - }, - "navSystemStatus_Flags_e": { - "_source": "inav/src/main/navigation/navigation.h", - "MW_NAV_FLAG_ADJUSTING_POSITION": "1 << 0", - "MW_NAV_FLAG_ADJUSTING_ALTITUDE": "1 << 1" - }, - "navSystemStatus_Mode_e": { - "_source": "inav/src/main/navigation/navigation.h", - "MW_GPS_MODE_NONE": "0", - "MW_GPS_MODE_HOLD": "1", - "MW_GPS_MODE_RTH": "2", - "MW_GPS_MODE_NAV": "3", - "MW_GPS_MODE_EMERG": "15" - }, - "navSystemStatus_State_e": { - "_source": "inav/src/main/navigation/navigation.h", - "MW_NAV_STATE_NONE": "0", - "MW_NAV_STATE_RTH_START": "1", - "MW_NAV_STATE_RTH_ENROUTE": "2", - "MW_NAV_STATE_HOLD_INFINIT": "3", - "MW_NAV_STATE_HOLD_TIMED": "4", - "MW_NAV_STATE_WP_ENROUTE": "5", - "MW_NAV_STATE_PROCESS_NEXT": "6", - "MW_NAV_STATE_DO_JUMP": "7", - "MW_NAV_STATE_LAND_START": "8", - "MW_NAV_STATE_LAND_IN_PROGRESS": "9", - "MW_NAV_STATE_LANDED": "10", - "MW_NAV_STATE_LAND_SETTLE": "11", - "MW_NAV_STATE_LAND_START_DESCENT": "12", - "MW_NAV_STATE_HOVER_ABOVE_HOME": "13", - "MW_NAV_STATE_EMERGENCY_LANDING": "14", - "MW_NAV_STATE_RTH_CLIMB": "15" - }, - "navWaypointActions_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_WP_ACTION_WAYPOINT": "1", - "NAV_WP_ACTION_HOLD_TIME": "3", - "NAV_WP_ACTION_RTH": "4", - "NAV_WP_ACTION_SET_POI": "5", - "NAV_WP_ACTION_JUMP": "6", - "NAV_WP_ACTION_SET_HEAD": "7", - "NAV_WP_ACTION_LAND": "8" - }, - "navWaypointFlags_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_WP_FLAG_HOME": "72", - "NAV_WP_FLAG_LAST": "165" - }, - "navWaypointHeadings_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_WP_HEAD_MODE_NONE": "0", - "NAV_WP_HEAD_MODE_POI": "1", - "NAV_WP_HEAD_MODE_FIXED": "2" - }, - "navWaypointP3Flags_e": { - "_source": "inav/src/main/navigation/navigation.h", - "NAV_WP_ALTMODE": "(1<<0)", - "NAV_WP_USER1": "(1<<1)", - "NAV_WP_USER2": "(1<<2)", - "NAV_WP_USER3": "(1<<3)", - "NAV_WP_USER4": "(1<<4)" - }, - "opflowQuality_e": { - "_source": "inav/src/main/sensors/opflow.h", - "OPFLOW_QUALITY_INVALID": "0", - "OPFLOW_QUALITY_VALID": "1" - }, - "opticalFlowSensor_e": { - "_source": "inav/src/main/sensors/opflow.h", - "OPFLOW_NONE": "0", - "OPFLOW_CXOF": "1", - "OPFLOW_MSP": "2", - "OPFLOW_FAKE": "3" - }, - "osd_adsb_warning_style_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_ADSB_WARNING_STYLE_COMPACT": "0", - "OSD_ADSB_WARNING_STYLE_EXTENDED": "1" - }, - "osd_ahi_style_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_AHI_STYLE_DEFAULT": "0", - "OSD_AHI_STYLE_LINE": "1" - }, - "osd_alignment_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_ALIGN_LEFT": "0", - "OSD_ALIGN_RIGHT": "1" - }, - "osd_crosshairs_style_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_CROSSHAIRS_STYLE_DEFAULT": "0", - "OSD_CROSSHAIRS_STYLE_AIRCRAFT": "1", - "OSD_CROSSHAIRS_STYLE_TYPE3": "2", - "OSD_CROSSHAIRS_STYLE_TYPE4": "3", - "OSD_CROSSHAIRS_STYLE_TYPE5": "4", - "OSD_CROSSHAIRS_STYLE_TYPE6": "5", - "OSD_CROSSHAIRS_STYLE_TYPE7": "6" - }, - "osd_crsf_lq_format_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_CRSF_LQ_TYPE1": "0", - "OSD_CRSF_LQ_TYPE2": "1", - "OSD_CRSF_LQ_TYPE3": "2" - }, - "osd_items_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_RSSI_VALUE": "0", - "OSD_MAIN_BATT_VOLTAGE": "1", - "OSD_CROSSHAIRS": "2", - "OSD_ARTIFICIAL_HORIZON": "3", - "OSD_HORIZON_SIDEBARS": "4", - "OSD_ONTIME": "5", - "OSD_FLYTIME": "6", - "OSD_FLYMODE": "7", - "OSD_CRAFT_NAME": "8", - "OSD_THROTTLE_POS": "9", - "OSD_VTX_CHANNEL": "10", - "OSD_CURRENT_DRAW": "11", - "OSD_MAH_DRAWN": "12", - "OSD_GPS_SPEED": "13", - "OSD_GPS_SATS": "14", - "OSD_ALTITUDE": "15", - "OSD_ROLL_PIDS": "16", - "OSD_PITCH_PIDS": "17", - "OSD_YAW_PIDS": "18", - "OSD_POWER": "19", - "OSD_GPS_LON": "20", - "OSD_GPS_LAT": "21", - "OSD_HOME_DIR": "22", - "OSD_HOME_DIST": "23", - "OSD_HEADING": "24", - "OSD_VARIO": "25", - "OSD_VERTICAL_SPEED_INDICATOR": "26", - "OSD_AIR_SPEED": "27", - "OSD_ONTIME_FLYTIME": "28", - "OSD_RTC_TIME": "29", - "OSD_MESSAGES": "30", - "OSD_GPS_HDOP": "31", - "OSD_MAIN_BATT_CELL_VOLTAGE": "32", - "OSD_SCALED_THROTTLE_POS": "33", - "OSD_HEADING_GRAPH": "34", - "OSD_EFFICIENCY_MAH_PER_KM": "35", - "OSD_WH_DRAWN": "36", - "OSD_BATTERY_REMAINING_CAPACITY": "37", - "OSD_BATTERY_REMAINING_PERCENT": "38", - "OSD_EFFICIENCY_WH_PER_KM": "39", - "OSD_TRIP_DIST": "40", - "OSD_ATTITUDE_PITCH": "41", - "OSD_ATTITUDE_ROLL": "42", - "OSD_MAP_NORTH": "43", - "OSD_MAP_TAKEOFF": "44", - "OSD_RADAR": "45", - "OSD_WIND_SPEED_HORIZONTAL": "46", - "OSD_WIND_SPEED_VERTICAL": "47", - "OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH": "48", - "OSD_REMAINING_DISTANCE_BEFORE_RTH": "49", - "OSD_HOME_HEADING_ERROR": "50", - "OSD_COURSE_HOLD_ERROR": "51", - "OSD_COURSE_HOLD_ADJUSTMENT": "52", - "OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE": "53", - "OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE": "54", - "OSD_POWER_SUPPLY_IMPEDANCE": "55", - "OSD_LEVEL_PIDS": "56", - "OSD_POS_XY_PIDS": "57", - "OSD_POS_Z_PIDS": "58", - "OSD_VEL_XY_PIDS": "59", - "OSD_VEL_Z_PIDS": "60", - "OSD_HEADING_P": "61", - "OSD_BOARD_ALIGN_ROLL": "62", - "OSD_BOARD_ALIGN_PITCH": "63", - "OSD_RC_EXPO": "64", - "OSD_RC_YAW_EXPO": "65", - "OSD_THROTTLE_EXPO": "66", - "OSD_PITCH_RATE": "67", - "OSD_ROLL_RATE": "68", - "OSD_YAW_RATE": "69", - "OSD_MANUAL_RC_EXPO": "70", - "OSD_MANUAL_RC_YAW_EXPO": "71", - "OSD_MANUAL_PITCH_RATE": "72", - "OSD_MANUAL_ROLL_RATE": "73", - "OSD_MANUAL_YAW_RATE": "74", - "OSD_NAV_FW_CRUISE_THR": "75", - "OSD_NAV_FW_PITCH2THR": "76", - "OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "77", - "OSD_DEBUG": "78", - "OSD_FW_ALT_PID_OUTPUTS": "79", - "OSD_FW_POS_PID_OUTPUTS": "80", - "OSD_MC_VEL_X_PID_OUTPUTS": "81", - "OSD_MC_VEL_Y_PID_OUTPUTS": "82", - "OSD_MC_VEL_Z_PID_OUTPUTS": "83", - "OSD_MC_POS_XYZ_P_OUTPUTS": "84", - "OSD_3D_SPEED": "85", - "OSD_IMU_TEMPERATURE": "86", - "OSD_BARO_TEMPERATURE": "87", - "OSD_TEMP_SENSOR_0_TEMPERATURE": "88", - "OSD_TEMP_SENSOR_1_TEMPERATURE": "89", - "OSD_TEMP_SENSOR_2_TEMPERATURE": "90", - "OSD_TEMP_SENSOR_3_TEMPERATURE": "91", - "OSD_TEMP_SENSOR_4_TEMPERATURE": "92", - "OSD_TEMP_SENSOR_5_TEMPERATURE": "93", - "OSD_TEMP_SENSOR_6_TEMPERATURE": "94", - "OSD_TEMP_SENSOR_7_TEMPERATURE": "95", - "OSD_ALTITUDE_MSL": "96", - "OSD_PLUS_CODE": "97", - "OSD_MAP_SCALE": "98", - "OSD_MAP_REFERENCE": "99", - "OSD_GFORCE": "100", - "OSD_GFORCE_X": "101", - "OSD_GFORCE_Y": "102", - "OSD_GFORCE_Z": "103", - "OSD_RC_SOURCE": "104", - "OSD_VTX_POWER": "105", - "OSD_ESC_RPM": "106", - "OSD_ESC_TEMPERATURE": "107", - "OSD_AZIMUTH": "108", - "OSD_RSSI_DBM": "109", - "OSD_LQ_UPLINK": "110", - "OSD_SNR_DB": "111", - "OSD_TX_POWER_UPLINK": "112", - "OSD_GVAR_0": "113", - "OSD_GVAR_1": "114", - "OSD_GVAR_2": "115", - "OSD_GVAR_3": "116", - "OSD_TPA": "117", - "OSD_NAV_FW_CONTROL_SMOOTHNESS": "118", - "OSD_VERSION": "119", - "OSD_RANGEFINDER": "120", - "OSD_PLIMIT_REMAINING_BURST_TIME": "121", - "OSD_PLIMIT_ACTIVE_CURRENT_LIMIT": "122", - "OSD_PLIMIT_ACTIVE_POWER_LIMIT": "123", - "OSD_GLIDESLOPE": "124", - "OSD_GPS_MAX_SPEED": "125", - "OSD_3D_MAX_SPEED": "126", - "OSD_AIR_MAX_SPEED": "127", - "OSD_ACTIVE_PROFILE": "128", - "OSD_MISSION": "129", - "OSD_SWITCH_INDICATOR_0": "130", - "OSD_SWITCH_INDICATOR_1": "131", - "OSD_SWITCH_INDICATOR_2": "132", - "OSD_SWITCH_INDICATOR_3": "133", - "OSD_TPA_TIME_CONSTANT": "134", - "OSD_FW_LEVEL_TRIM": "135", - "OSD_GLIDE_TIME_REMAINING": "136", - "OSD_GLIDE_RANGE": "137", - "OSD_CLIMB_EFFICIENCY": "138", - "OSD_NAV_WP_MULTI_MISSION_INDEX": "139", - "OSD_GROUND_COURSE": "140", - "OSD_CROSS_TRACK_ERROR": "141", - "OSD_PILOT_NAME": "142", - "OSD_PAN_SERVO_CENTRED": "143", - "OSD_MULTI_FUNCTION": "144", - "OSD_ODOMETER": "145", - "OSD_PILOT_LOGO": "146", - "OSD_CUSTOM_ELEMENT_1": "147", - "OSD_CUSTOM_ELEMENT_2": "148", - "OSD_CUSTOM_ELEMENT_3": "149", - "OSD_ADSB_WARNING": "150", - "OSD_ADSB_INFO": "151", - "OSD_BLACKBOX": "152", - "OSD_FORMATION_FLIGHT": "153", - "OSD_CUSTOM_ELEMENT_4": "154", - "OSD_CUSTOM_ELEMENT_5": "155", - "OSD_CUSTOM_ELEMENT_6": "156", - "OSD_CUSTOM_ELEMENT_7": "157", - "OSD_CUSTOM_ELEMENT_8": "158", - "OSD_LQ_DOWNLINK": "159", - "OSD_RX_POWER_DOWNLINK": "160", - "OSD_RX_BAND": "161", - "OSD_RX_MODE": "162", - "OSD_COURSE_TO_FENCE": "163", - "OSD_H_DIST_TO_FENCE": "164", - "OSD_V_DIST_TO_FENCE": "165", - "OSD_NAV_FW_ALT_CONTROL_RESPONSE": "166", - "OSD_NAV_MIN_GROUND_SPEED": "167", - "OSD_THROTTLE_GAUGE": "168", - "OSD_ITEM_COUNT": "169" - }, - "osd_sidebar_arrow_e": { - "_source": "inav/src/main/io/osd_grid.c", - "OSD_SIDEBAR_ARROW_NONE": "0", - "OSD_SIDEBAR_ARROW_UP": "1", - "OSD_SIDEBAR_ARROW_DOWN": "2" - }, - "osd_sidebar_scroll_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_SIDEBAR_SCROLL_NONE": "0", - "OSD_SIDEBAR_SCROLL_ALTITUDE": "1", - "OSD_SIDEBAR_SCROLL_SPEED": "2", - "OSD_SIDEBAR_SCROLL_HOME_DISTANCE": "3", - "OSD_SIDEBAR_SCROLL_MAX": "OSD_SIDEBAR_SCROLL_HOME_DISTANCE" - }, - "osd_SpeedTypes_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_SPEED_TYPE_GROUND": "0", - "OSD_SPEED_TYPE_AIR": "1", - "OSD_SPEED_TYPE_3D": "2", - "OSD_SPEED_TYPE_MIN_GROUND": "3" - }, - "osd_stats_energy_unit_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_STATS_ENERGY_UNIT_MAH": "0", - "OSD_STATS_ENERGY_UNIT_WH": "1" - }, - "osd_unit_e": { - "_source": "inav/src/main/io/osd.h", - "OSD_UNIT_IMPERIAL": "0", - "OSD_UNIT_METRIC": "1", - "OSD_UNIT_METRIC_MPH": "2", - "OSD_UNIT_UK": "3", - "OSD_UNIT_GA": "4", - "OSD_UNIT_MAX": "OSD_UNIT_GA" - }, - "osdCustomElementType_e": { - "_source": "inav/src/main/io/osd/custom_elements.h", - "CUSTOM_ELEMENT_TYPE_NONE": "0", - "CUSTOM_ELEMENT_TYPE_TEXT": "1", - "CUSTOM_ELEMENT_TYPE_ICON_STATIC": "2", - "CUSTOM_ELEMENT_TYPE_ICON_GV": "3", - "CUSTOM_ELEMENT_TYPE_ICON_LC": "4", - "CUSTOM_ELEMENT_TYPE_GV_1": "5", - "CUSTOM_ELEMENT_TYPE_GV_2": "6", - "CUSTOM_ELEMENT_TYPE_GV_3": "7", - "CUSTOM_ELEMENT_TYPE_GV_4": "8", - "CUSTOM_ELEMENT_TYPE_GV_5": "9", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_1": "10", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_2": "11", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_1": "12", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_2": "13", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_1": "14", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_2": "15", - "CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_1": "16", - "CUSTOM_ELEMENT_TYPE_LC_1": "17", - "CUSTOM_ELEMENT_TYPE_LC_2": "18", - "CUSTOM_ELEMENT_TYPE_LC_3": "19", - "CUSTOM_ELEMENT_TYPE_LC_4": "20", - "CUSTOM_ELEMENT_TYPE_LC_5": "21", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_1": "22", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_2": "23", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_1": "24", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_2": "25", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_1": "26", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_2": "27", - "CUSTOM_ELEMENT_TYPE_LC_FLOAT_4_1": "28", - "CUSTOM_ELEMENT_TYPE_END": "29" - }, - "osdCustomElementTypeVisibility_e": { - "_source": "inav/src/main/io/osd/custom_elements.h", - "CUSTOM_ELEMENT_VISIBILITY_ALWAYS": "0", - "CUSTOM_ELEMENT_VISIBILITY_GV": "1", - "CUSTOM_ELEMENT_VISIBILITY_LOGIC_CON": "2" - }, - "osdDrawPointType_e": { - "_source": "inav/src/main/io/osd_common.h", - "OSD_DRAW_POINT_TYPE_GRID": "0", - "OSD_DRAW_POINT_TYPE_PIXEL": "1" - }, - "osdDriver_e": { - "_source": "inav/src/main/drivers/osd.h", - "OSD_DRIVER_NONE": "0", - "OSD_DRIVER_MAX7456": "1" - }, - "osdSpeedSource_e": { - "_source": "inav/src/main/io/osd_common.h", - "OSD_SPEED_SOURCE_GROUND": "0", - "OSD_SPEED_SOURCE_3D": "1", - "OSD_SPEED_SOURCE_AIR": "2" - }, - "outputMode_e": { - "_source": "inav/src/main/flight/mixer.h", - "OUTPUT_MODE_AUTO": "0", - "OUTPUT_MODE_MOTORS": "1", - "OUTPUT_MODE_SERVOS": "2", - "OUTPUT_MODE_LED": "3" - }, - "pageId_e": { - "_source": "inav/src/main/io/dashboard.h", - "PAGE_WELCOME": "0", - "PAGE_ARMED": "1", - "PAGE_STATUS": "2" - }, - "persistentObjectId_e": { - "_source": "inav/src/main/drivers/persistent.h", - "PERSISTENT_OBJECT_MAGIC": "0", - "PERSISTENT_OBJECT_RESET_REASON": "1", - "PERSISTENT_OBJECT_COUNT": "2" - }, - "pidAutotuneState_e": { - "_source": "inav/src/main/flight/pid_autotune.c", - "DEMAND_TOO_LOW": "0", - "DEMAND_UNDERSHOOT": "1", - "DEMAND_OVERSHOOT": "2", - "TUNE_UPDATED": "3" - }, - "pidControllerFlags_e": { - "_source": "inav/src/main/common/fp_pid.h", - "PID_DTERM_FROM_ERROR": "1 << 0", - "PID_ZERO_INTEGRATOR": "1 << 1", - "PID_SHRINK_INTEGRATOR": "1 << 2", - "PID_LIMIT_INTEGRATOR": "1 << 3", - "PID_FREEZE_INTEGRATOR": "1 << 4" - }, - "pidIndex_e": { - "_source": "inav/src/main/flight/pid.h", - "PID_ROLL": "0", - "PID_PITCH": "1", - "PID_YAW": "2", - "PID_POS_Z": "3", - "PID_POS_XY": "4", - "PID_VEL_XY": "5", - "PID_SURFACE": "6", - "PID_LEVEL": "7", - "PID_HEADING": "8", - "PID_VEL_Z": "9", - "PID_POS_HEADING": "10", - "PID_ITEM_COUNT": "11" - }, - "pidType_e": { - "_source": "inav/src/main/flight/pid.h", - "PID_TYPE_NONE": "0", - "PID_TYPE_PID": "1", - "PID_TYPE_PIFF": "2", - "PID_TYPE_AUTO": "3" - }, - "pinLabel_e": { - "_source": "inav/src/main/drivers/pwm_mapping.h", - "PIN_LABEL_NONE": "0", - "PIN_LABEL_LED": "1" - }, - "pitotSensor_e": { - "_source": "inav/src/main/sensors/pitotmeter.h", - "PITOT_NONE": "0", - "PITOT_AUTODETECT": "1", - "PITOT_MS4525": "2", - "PITOT_ADC": "3", - "PITOT_VIRTUAL": "4", - "PITOT_FAKE": "5", - "PITOT_MSP": "6", - "PITOT_DLVR": "7" - }, - "pollType_e": { - "_source": "inav/src/main/io/smartport_master.c", - "PT_ACTIVE_ID": "0", - "PT_INACTIVE_ID": "1" - }, - "portMode_t": { - "_source": "inav/src/main/drivers/serial.h", - "MODE_RX": "1 << 0", - "MODE_TX": "1 << 1", - "MODE_RXTX": "MODE_RX | MODE_TX" - }, - "portOptions_t": { - "_source": "inav/src/main/drivers/serial.h", - "SERIAL_NOT_INVERTED": "0 << 0", - "SERIAL_INVERTED": "1 << 0", - "SERIAL_STOPBITS_1": "0 << 1", - "SERIAL_STOPBITS_2": "1 << 1", - "SERIAL_PARITY_NO": "0 << 2", - "SERIAL_PARITY_EVEN": "1 << 2", - "SERIAL_UNIDIR": "0 << 3", - "SERIAL_BIDIR": "1 << 3", - "SERIAL_BIDIR_OD": "0 << 4", - "SERIAL_BIDIR_PP": "1 << 4", - "SERIAL_BIDIR_NOPULL": "1 << 5", - "SERIAL_BIDIR_UP": "0 << 5", - "SERIAL_LONGSTOP": "0 << 6", - "SERIAL_SHORTSTOP": "1 << 6" - }, - "portSharing_e": { - "_source": "inav/src/main/io/serial.h", - "PORTSHARING_UNUSED": "0", - "PORTSHARING_NOT_SHARED": "1", - "PORTSHARING_SHARED": "2" - }, - "pwmInitError_e": { - "_source": "inav/src/main/drivers/pwm_mapping.h", - "PWM_INIT_ERROR_NONE": "0", - "PWM_INIT_ERROR_TOO_MANY_MOTORS": "1", - "PWM_INIT_ERROR_TOO_MANY_SERVOS": "2", - "PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS": "3", - "PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS": "4", - "PWM_INIT_ERROR_TIMER_INIT_FAILED": "5" - }, - "quadrant_e": { - "_source": "inav/src/main/io/ledstrip.c", - "QUADRANT_NORTH": "1 << 0", - "QUADRANT_SOUTH": "1 << 1", - "QUADRANT_EAST": "1 << 2", - "QUADRANT_WEST": "1 << 3", - "QUADRANT_NORTH_EAST": "1 << 4", - "QUADRANT_SOUTH_EAST": "1 << 5", - "QUADRANT_NORTH_WEST": "1 << 6", - "QUADRANT_SOUTH_WEST": "1 << 7", - "QUADRANT_NONE": "1 << 8", - "QUADRANT_NOTDIAG": "1 << 9", - "QUADRANT_ANY": "QUADRANT_NORTH | QUADRANT_SOUTH | QUADRANT_EAST | QUADRANT_WEST | QUADRANT_NONE" - }, - "QUADSPIClockDivider_e": { - "_source": "inav/src/main/drivers/bus_quadspi.h", - "QUADSPI_CLOCK_INITIALISATION": "255", - "QUADSPI_CLOCK_SLOW": "19", - "QUADSPI_CLOCK_STANDARD": "9", - "QUADSPI_CLOCK_FAST": "3", - "QUADSPI_CLOCK_ULTRAFAST": "1" - }, - "QUADSPIDevice": { - "_source": "inav/src/main/drivers/bus_quadspi.h", - "QUADSPIINVALID": "-1", - "QUADSPIDEV_1": "0" - }, - "quadSpiMode_e": { - "_source": "inav/src/main/drivers/bus_quadspi.h", - "QUADSPI_MODE_BK1_ONLY": "0", - "QUADSPI_MODE_BK2_ONLY": "1", - "QUADSPI_MODE_DUAL_FLASH": "2" - }, - "rangefinderType_e": { - "_source": "inav/src/main/sensors/rangefinder.h", - "RANGEFINDER_NONE": "0", - "RANGEFINDER_SRF10": "1", - "RANGEFINDER_VL53L0X": "2", - "RANGEFINDER_MSP": "3", - "RANGEFINDER_BENEWAKE": "4", - "RANGEFINDER_VL53L1X": "5", - "RANGEFINDER_US42": "6", - "RANGEFINDER_TOF10102I2C": "7", - "RANGEFINDER_FAKE": "8", - "RANGEFINDER_TERARANGER_EVO": "9", - "RANGEFINDER_USD1_V0": "10", - "RANGEFINDER_NANORADAR": "11" - }, - "rc_alias_e": { - "_source": "inav/src/main/fc/rc_controls.h", - "ROLL": "0", - "PITCH": "1", - "YAW": "2", - "THROTTLE": "3", - "AUX1": "4", - "AUX2": "5", - "AUX3": "6", - "AUX4": "7", - "AUX5": "8", - "AUX6": "9", - "AUX7": "10", - "AUX8": "11", - "AUX9": "12", - "AUX10": "13", - "AUX11": "14", - "AUX12": "15", - "AUX13": "16", - "AUX14": "17", - "AUX15": [ - "(18)", - "USE_34CHANNELS" - ], - "AUX16": [ - "(19)", - "USE_34CHANNELS" - ], - "AUX17": [ - "(20)", - "USE_34CHANNELS" - ], - "AUX18": [ - "(21)", - "USE_34CHANNELS" - ], - "AUX19": [ - "(22)", - "USE_34CHANNELS" - ], - "AUX20": [ - "(23)", - "USE_34CHANNELS" - ], - "AUX21": [ - "(24)", - "USE_34CHANNELS" - ], - "AUX22": [ - "(25)", - "USE_34CHANNELS" - ], - "AUX23": [ - "(26)", - "USE_34CHANNELS" - ], - "AUX24": [ - "(27)", - "USE_34CHANNELS" - ], - "AUX25": [ - "(28)", - "USE_34CHANNELS" - ], - "AUX26": [ - "(29)", - "USE_34CHANNELS" - ], - "AUX27": [ - "(30)", - "USE_34CHANNELS" - ], - "AUX28": [ - "(31)", - "USE_34CHANNELS" - ], - "AUX29": [ - "(32)", - "USE_34CHANNELS" - ], - "AUX30": [ - "(33)", - "USE_34CHANNELS" - ] - }, - "RCDEVICE_5key_connection_event_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN": "1", - "RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE": "2" - }, - "rcdevice_5key_simulation_operation_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE": "0", - "RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET": "1", - "RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT": "2", - "RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT": "3", - "RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP": "4", - "RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN": "5" - }, - "rcdevice_camera_control_opeation_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN": "0", - "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN": "1", - "RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE": "2", - "RCDEVICE_PROTOCOL_CAM_CTRL_START_RECORDING": "3", - "RCDEVICE_PROTOCOL_CAM_CTRL_STOP_RECORDING": "4", - "RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION": "255" - }, - "rcdevice_features_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON": "(1 << 0)", - "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON": "(1 << 1)", - "RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE": "(1 << 2)", - "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE": "(1 << 3)", - "RCDEVICE_PROTOCOL_FEATURE_START_RECORDING": "(1 << 6)", - "RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING": "(1 << 7)", - "RCDEVICE_PROTOCOL_FEATURE_CMS_MENU": "(1 << 8)" - }, - "rcdevice_protocol_version_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_PROTOCOL_RCSPLIT_VERSION": "0", - "RCDEVICE_PROTOCOL_VERSION_1_0": "1", - "RCDEVICE_PROTOCOL_UNKNOWN": "2" - }, - "rcdeviceCamSimulationKeyEvent_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_CAM_KEY_NONE": "0", - "RCDEVICE_CAM_KEY_ENTER": "1", - "RCDEVICE_CAM_KEY_LEFT": "2", - "RCDEVICE_CAM_KEY_UP": "3", - "RCDEVICE_CAM_KEY_RIGHT": "4", - "RCDEVICE_CAM_KEY_DOWN": "5", - "RCDEVICE_CAM_KEY_CONNECTION_CLOSE": "6", - "RCDEVICE_CAM_KEY_CONNECTION_OPEN": "7", - "RCDEVICE_CAM_KEY_RELEASE": "8" - }, - "rcdeviceResponseStatus_e": { - "_source": "inav/src/main/io/rcdevice.h", - "RCDEVICE_RESP_SUCCESS": "0", - "RCDEVICE_RESP_INCORRECT_CRC": "1", - "RCDEVICE_RESP_TIMEOUT": "2" - }, - "resolutionType_e": { - "_source": "inav/src/main/io/displayport_msp_osd.c", - "SD_3016": "0", - "HD_5018": "1", - "HD_3016": "2", - "HD_6022": "3", - "HD_5320": "4" - }, - "resourceOwner_e": { - "_source": "inav/src/main/drivers/resource.h", - "OWNER_FREE": "0", - "OWNER_PWMIO": "1", - "OWNER_MOTOR": "2", - "OWNER_SERVO": "3", - "OWNER_SOFTSERIAL": "4", - "OWNER_ADC": "5", - "OWNER_SERIAL": "6", - "OWNER_TIMER": "7", - "OWNER_RANGEFINDER": "8", - "OWNER_SYSTEM": "9", - "OWNER_SPI": "10", - "OWNER_QUADSPI": "11", - "OWNER_I2C": "12", - "OWNER_SDCARD": "13", - "OWNER_FLASH": "14", - "OWNER_USB": "15", - "OWNER_BEEPER": "16", - "OWNER_OSD": "17", - "OWNER_BARO": "18", - "OWNER_MPU": "19", - "OWNER_INVERTER": "20", - "OWNER_LED_STRIP": "21", - "OWNER_LED": "22", - "OWNER_RX": "23", - "OWNER_TX": "24", - "OWNER_VTX": "25", - "OWNER_SPI_PREINIT": "26", - "OWNER_COMPASS": "27", - "OWNER_TEMPERATURE": "28", - "OWNER_1WIRE": "29", - "OWNER_AIRSPEED": "30", - "OWNER_OLED_DISPLAY": "31", - "OWNER_PINIO": "32", - "OWNER_IRLOCK": "33", - "OWNER_TOTAL_COUNT": "34" - }, - "resourceType_e": { - "_source": "inav/src/main/drivers/resource.h", - "RESOURCE_NONE": "0", - "RESOURCE_INPUT": "1", - "RESOURCE_TIMER": "2", - "RESOURCE_UART_TX": "3", - "RESOURCE_EXTI": "4", - "RESOURCE_I2C_SCL": "5", - "RESOURCE_SPI_SCK": "6", - "RESOURCE_QUADSPI_CLK": "7", - "RESOURCE_QUADSPI_BK1IO2": "8", - "RESOURCE_QUADSPI_BK2IO0": "9", - "RESOURCE_QUADSPI_BK2IO3": "10", - "RESOURCE_ADC_CH1": "11", - "RESOURCE_RX_CE": "12", - "RESOURCE_TOTAL_COUNT": "13" - }, - "reversibleMotorsThrottleState_e": { - "_source": "inav/src/main/flight/mixer.h", - "MOTOR_DIRECTION_FORWARD": "0", - "MOTOR_DIRECTION_BACKWARD": "1", - "MOTOR_DIRECTION_DEADBAND": "2" - }, - "rollPitchStatus_e": { - "_source": "inav/src/main/fc/rc_controls.h", - "NOT_CENTERED": "0", - "CENTERED": "1" - }, - "rssiSource_e": { - "_source": "inav/src/main/rx/rx.h", - "RSSI_SOURCE_NONE": "0", - "RSSI_SOURCE_AUTO": "1", - "RSSI_SOURCE_ADC": "2", - "RSSI_SOURCE_RX_CHANNEL": "3", - "RSSI_SOURCE_RX_PROTOCOL": "4", - "RSSI_SOURCE_MSP": "5" - }, - "rthState_e": { - "_source": "inav/src/main/flight/failsafe.h", - "RTH_IDLE": "0", - "RTH_IN_PROGRESS": "1", - "RTH_HAS_LANDED": "2" - }, - "rthTargetMode_e": { - "_source": "inav/src/main/navigation/navigation_private.h", - "RTH_HOME_ENROUTE_INITIAL": "0", - "RTH_HOME_ENROUTE_PROPORTIONAL": "1", - "RTH_HOME_ENROUTE_FINAL": "2", - "RTH_HOME_FINAL_LOITER": "3", - "RTH_HOME_FINAL_LAND": "4" - }, - "rthTrackbackMode_e": { - "_source": "inav/src/main/navigation/navigation.h", - "RTH_TRACKBACK_OFF": "0", - "RTH_TRACKBACK_ON": "1", - "RTH_TRACKBACK_FS": "2" - }, - "rxFrameState_e": { - "_source": "inav/src/main/rx/rx.h", - "RX_FRAME_PENDING": "0", - "RX_FRAME_COMPLETE": "(1 << 0)", - "RX_FRAME_FAILSAFE": "(1 << 1)", - "RX_FRAME_PROCESSING_REQUIRED": "(1 << 2)", - "RX_FRAME_DROPPED": "(1 << 3)" - }, - "rxReceiverType_e": { - "_source": "inav/src/main/rx/rx.h", - "RX_TYPE_NONE": "0", - "RX_TYPE_SERIAL": "1", - "RX_TYPE_MSP": "2", - "RX_TYPE_SIM": "3" - }, - "rxSerialReceiverType_e": { - "_source": "inav/src/main/rx/rx.h", - "SERIALRX_SPEKTRUM1024": "0", - "SERIALRX_SPEKTRUM2048": "1", - "SERIALRX_SBUS": "2", - "SERIALRX_SUMD": "3", - "SERIALRX_IBUS": "4", - "SERIALRX_JETIEXBUS": "5", - "SERIALRX_CRSF": "6", - "SERIALRX_FPORT": "7", - "SERIALRX_SBUS_FAST": "8", - "SERIALRX_FPORT2": "9", - "SERIALRX_SRXL2": "10", - "SERIALRX_GHST": "11", - "SERIALRX_MAVLINK": "12", - "SERIALRX_FBUS": "13", - "SERIALRX_SBUS2": "14" - }, - "safehomeUsageMode_e": { - "_source": "inav/src/main/navigation/navigation.h", - "SAFEHOME_USAGE_OFF": "0", - "SAFEHOME_USAGE_RTH": "1", - "SAFEHOME_USAGE_RTH_FS": "2" - }, - "sbasMode_e": { - "_source": "inav/src/main/io/gps.h", - "SBAS_AUTO": "0", - "SBAS_EGNOS": "1", - "SBAS_WAAS": "2", - "SBAS_MSAS": "3", - "SBAS_GAGAN": "4", - "SBAS_SPAN": "5", - "SBAS_NONE": "6" - }, - "sbusDecoderState_e": { - "_source": "inav/src/main/rx/sbus.c", - "STATE_SBUS_SYNC": "0", - "STATE_SBUS_PAYLOAD": "1", - "STATE_SBUS26_PAYLOAD": "2", - "STATE_SBUS_WAIT_SYNC": "3" - }, - "sdcardBlockOperation_e": { - "_source": "inav/src/main/drivers/sdcard/sdcard.h", - "SDCARD_BLOCK_OPERATION_READ": "0", - "SDCARD_BLOCK_OPERATION_WRITE": "1", - "SDCARD_BLOCK_OPERATION_ERASE": "2" - }, - "sdcardOperationStatus_e": { - "_source": "inav/src/main/drivers/sdcard/sdcard.h", - "SDCARD_OPERATION_IN_PROGRESS": "0", - "SDCARD_OPERATION_BUSY": "1", - "SDCARD_OPERATION_SUCCESS": "2", - "SDCARD_OPERATION_FAILURE": "3" - }, - "sdcardReceiveBlockStatus_e": { - "_source": "inav/src/main/drivers/sdcard/sdcard_spi.c", - "SDCARD_RECEIVE_SUCCESS": "0", - "SDCARD_RECEIVE_BLOCK_IN_PROGRESS": "1", - "SDCARD_RECEIVE_ERROR": "2" - }, - "sdcardState_e": { - "_source": "inav/src/main/drivers/sdcard/sdcard_impl.h", - "SDCARD_STATE_NOT_PRESENT": "0", - "SDCARD_STATE_RESET": "1", - "SDCARD_STATE_CARD_INIT_IN_PROGRESS": "2", - "SDCARD_STATE_INITIALIZATION_RECEIVE_CID": "3", - "SDCARD_STATE_READY": "4", - "SDCARD_STATE_READING": "5", - "SDCARD_STATE_SENDING_WRITE": "6", - "SDCARD_STATE_WAITING_FOR_WRITE": "7", - "SDCARD_STATE_WRITING_MULTIPLE_BLOCKS": "8", - "SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE": "9" - }, - "SDIODevice": { - "_source": "inav/src/main/drivers/sdio.h", - "SDIOINVALID": "-1", - "SDIODEV_1": "0", - "SDIODEV_2": "1" - }, - "sensor_align_e": { - "_source": "inav/src/main/drivers/sensor.h", - "ALIGN_DEFAULT": "0", - "CW0_DEG": "1", - "CW90_DEG": "2", - "CW180_DEG": "3", - "CW270_DEG": "4", - "CW0_DEG_FLIP": "5", - "CW90_DEG_FLIP": "6", - "CW180_DEG_FLIP": "7", - "CW270_DEG_FLIP": "8" - }, - "sensorIndex_e": { - "_source": "inav/src/main/sensors/sensors.h", - "SENSOR_INDEX_GYRO": "0", - "SENSOR_INDEX_ACC": "1", - "SENSOR_INDEX_BARO": "2", - "SENSOR_INDEX_MAG": "3", - "SENSOR_INDEX_RANGEFINDER": "4", - "SENSOR_INDEX_PITOT": "5", - "SENSOR_INDEX_OPFLOW": "6", - "SENSOR_INDEX_COUNT": "7" - }, - "sensors_e": { - "_source": "inav/src/main/sensors/sensors.h", - "SENSOR_GYRO": "1 << 0", - "SENSOR_ACC": "1 << 1", - "SENSOR_BARO": "1 << 2", - "SENSOR_MAG": "1 << 3", - "SENSOR_RANGEFINDER": "1 << 4", - "SENSOR_PITOT": "1 << 5", - "SENSOR_OPFLOW": "1 << 6", - "SENSOR_GPS": "1 << 7", - "SENSOR_GPSMAG": "1 << 8", - "SENSOR_TEMP": "1 << 9" - }, - "sensorTempCalState_e": { - "_source": "inav/src/main/sensors/sensors.h", - "SENSOR_TEMP_CAL_INITIALISE": "0", - "SENSOR_TEMP_CAL_IN_PROGRESS": "1", - "SENSOR_TEMP_CAL_COMPLETE": "2" - }, - "serialPortFunction_e": { - "_source": "inav/src/main/io/serial.h", - "FUNCTION_NONE": "0", - "FUNCTION_MSP": "(1 << 0)", - "FUNCTION_GPS": "(1 << 1)", - "FUNCTION_UNUSED_3": "(1 << 2)", - "FUNCTION_TELEMETRY_HOTT": "(1 << 3)", - "FUNCTION_TELEMETRY_LTM": "(1 << 4)", - "FUNCTION_TELEMETRY_SMARTPORT": "(1 << 5)", - "FUNCTION_RX_SERIAL": "(1 << 6)", - "FUNCTION_BLACKBOX": "(1 << 7)", - "FUNCTION_TELEMETRY_MAVLINK": "(1 << 8)", - "FUNCTION_TELEMETRY_IBUS": "(1 << 9)", - "FUNCTION_RCDEVICE": "(1 << 10)", - "FUNCTION_VTX_SMARTAUDIO": "(1 << 11)", - "FUNCTION_VTX_TRAMP": "(1 << 12)", - "FUNCTION_UNUSED_1": "(1 << 13)", - "FUNCTION_OPTICAL_FLOW": "(1 << 14)", - "FUNCTION_LOG": "(1 << 15)", - "FUNCTION_RANGEFINDER": "(1 << 16)", - "FUNCTION_VTX_FFPV": "(1 << 17)", - "FUNCTION_ESCSERIAL": "(1 << 18)", - "FUNCTION_TELEMETRY_SIM": "(1 << 19)", - "FUNCTION_FRSKY_OSD": "(1 << 20)", - "FUNCTION_DJI_HD_OSD": "(1 << 21)", - "FUNCTION_SERVO_SERIAL": "(1 << 22)", - "FUNCTION_TELEMETRY_SMARTPORT_MASTER": "(1 << 23)", - "FUNCTION_UNUSED_2": "(1 << 24)", - "FUNCTION_MSP_OSD": "(1 << 25)", - "FUNCTION_GIMBAL": "(1 << 26)", - "FUNCTION_GIMBAL_HEADTRACKER": "(1 << 27)" - }, - "serialPortIdentifier_e": { - "_source": "inav/src/main/io/serial.h", - "SERIAL_PORT_NONE": "-1", - "SERIAL_PORT_USART1": "0", - "SERIAL_PORT_USART2": "1", - "SERIAL_PORT_USART3": "2", - "SERIAL_PORT_USART4": "3", - "SERIAL_PORT_USART5": "4", - "SERIAL_PORT_USART6": "5", - "SERIAL_PORT_USART7": "6", - "SERIAL_PORT_USART8": "7", - "SERIAL_PORT_USB_VCP": "20", - "SERIAL_PORT_SOFTSERIAL1": "30", - "SERIAL_PORT_SOFTSERIAL2": "31", - "SERIAL_PORT_IDENTIFIER_MAX": "SERIAL_PORT_SOFTSERIAL2" - }, - "servoAutotrimState_e": { - "_source": "inav/src/main/flight/servos.c", - "AUTOTRIM_IDLE": "0", - "AUTOTRIM_COLLECTING": "1", - "AUTOTRIM_SAVE_PENDING": "2", - "AUTOTRIM_DONE": "3" - }, - "servoIndex_e": { - "_source": "inav/src/main/flight/servos.h", - "SERVO_GIMBAL_PITCH": "0", - "SERVO_GIMBAL_ROLL": "1", - "SERVO_ELEVATOR": "2", - "SERVO_FLAPPERON_1": "3", - "SERVO_FLAPPERON_2": "4", - "SERVO_RUDDER": "5", - "SERVO_BICOPTER_LEFT": "4", - "SERVO_BICOPTER_RIGHT": "5", - "SERVO_DUALCOPTER_LEFT": "4", - "SERVO_DUALCOPTER_RIGHT": "5", - "SERVO_SINGLECOPTER_1": "3", - "SERVO_SINGLECOPTER_2": "4", - "SERVO_SINGLECOPTER_3": "5", - "SERVO_SINGLECOPTER_4": "6" - }, - "servoProtocolType_e": { - "_source": "inav/src/main/drivers/pwm_mapping.h", - "SERVO_TYPE_PWM": "0", - "SERVO_TYPE_SBUS": "1", - "SERVO_TYPE_SBUS_PWM": "2" - }, - "setting_mode_e": { - "_source": "inav/src/main/fc/settings.h", - "MODE_DIRECT": "(0 << SETTING_MODE_OFFSET)", - "MODE_LOOKUP": "(1 << SETTING_MODE_OFFSET)" - }, - "setting_section_e": { - "_source": "inav/src/main/fc/settings.h", - "MASTER_VALUE": "(0 << SETTING_SECTION_OFFSET)", - "PROFILE_VALUE": "(1 << SETTING_SECTION_OFFSET)", - "CONTROL_VALUE": "(2 << SETTING_SECTION_OFFSET)", - "BATTERY_CONFIG_VALUE": "(3 << SETTING_SECTION_OFFSET)", - "MIXER_CONFIG_VALUE": "(4 << SETTING_SECTION_OFFSET)", - "EZ_TUNE_VALUE": "(5 << SETTING_SECTION_OFFSET)" - }, - "setting_type_e": { - "_source": "inav/src/main/fc/settings.h", - "VAR_UINT8": "(0 << SETTING_TYPE_OFFSET)", - "VAR_INT8": "(1 << SETTING_TYPE_OFFSET)", - "VAR_UINT16": "(2 << SETTING_TYPE_OFFSET)", - "VAR_INT16": "(3 << SETTING_TYPE_OFFSET)", - "VAR_UINT32": "(4 << SETTING_TYPE_OFFSET)", - "VAR_FLOAT": "(5 << SETTING_TYPE_OFFSET)", - "VAR_STRING": "(6 << SETTING_TYPE_OFFSET)" - }, - "simATCommandState_e": { - "_source": "inav/src/main/telemetry/sim.c", - "SIM_AT_OK": "0", - "SIM_AT_ERROR": "1", - "SIM_AT_WAITING_FOR_RESPONSE": "2" - }, - "simModuleState_e": { - "_source": "inav/src/main/telemetry/sim.c", - "SIM_MODULE_NOT_DETECTED": "0", - "SIM_MODULE_NOT_REGISTERED": "1", - "SIM_MODULE_REGISTERED": "2" - }, - "simReadState_e": { - "_source": "inav/src/main/telemetry/sim.c", - "SIM_READSTATE_RESPONSE": "0", - "SIM_READSTATE_SMS": "1", - "SIM_READSTATE_SKIP": "2" - }, - "simTelemetryState_e": { - "_source": "inav/src/main/telemetry/sim.c", - "SIM_STATE_INIT": "0", - "SIM_STATE_INIT2": "1", - "SIM_STATE_INIT_ENTER_PIN": "2", - "SIM_STATE_SET_MODES": "3", - "SIM_STATE_SEND_SMS": "4", - "SIM_STATE_SEND_SMS_ENTER_MESSAGE": "5" - }, - "simTransmissionState_e": { - "_source": "inav/src/main/telemetry/sim.c", - "SIM_TX_NO": "0", - "SIM_TX_FS": "1", - "SIM_TX": "2" - }, - "simTxFlags_e": { - "_source": "inav/src/main/telemetry/sim.h", - "SIM_TX_FLAG": "(1 << 0)", - "SIM_TX_FLAG_FAILSAFE": "(1 << 1)", - "SIM_TX_FLAG_GPS": "(1 << 2)", - "SIM_TX_FLAG_ACC": "(1 << 3)", - "SIM_TX_FLAG_LOW_ALT": "(1 << 4)", - "SIM_TX_FLAG_RESPONSE": "(1 << 5)" - }, - "simulatorFlags_t": { - "_source": "inav/src/main/fc/runtime_config.h", - "HITL_RESET_FLAGS": "(0 << 0)", - "HITL_ENABLE": "(1 << 0)", - "HITL_SIMULATE_BATTERY": "(1 << 1)", - "HITL_MUTE_BEEPER": "(1 << 2)", - "HITL_USE_IMU": "(1 << 3)", - "HITL_HAS_NEW_GPS_DATA": "(1 << 4)", - "HITL_EXT_BATTERY_VOLTAGE": "(1 << 5)", - "HITL_AIRSPEED": "(1 << 6)", - "HITL_EXTENDED_FLAGS": "(1 << 7)", - "HITL_GPS_TIMEOUT": "(1 << 8)", - "HITL_PITOT_FAILURE": "(1 << 9)" - }, - "smartAudioVersion_e": { - "_source": "inav/src/main/io/vtx_smartaudio.h", - "SA_UNKNOWN": "0", - "SA_1_0": "1", - "SA_2_0": "2", - "SA_2_1": "3" - }, - "smartportFuelUnit_e": { - "_source": "inav/src/main/telemetry/telemetry.h", - "SMARTPORT_FUEL_UNIT_PERCENT": "0", - "SMARTPORT_FUEL_UNIT_MAH": "1", - "SMARTPORT_FUEL_UNIT_MWH": "2" - }, - "softSerialPortIndex_e": { - "_source": "inav/src/main/drivers/serial_softserial.h", - "SOFTSERIAL1": "0", - "SOFTSERIAL2": "1" - }, - "SPIClockSpeed_e": { - "_source": "inav/src/main/drivers/bus_spi.h", - "SPI_CLOCK_INITIALIZATON": "0", - "SPI_CLOCK_SLOW": "1", - "SPI_CLOCK_STANDARD": "2", - "SPI_CLOCK_FAST": "3", - "SPI_CLOCK_ULTRAFAST": "4" - }, - "SPIDevice": { - "_source": "inav/src/main/drivers/bus_spi.h", - "SPIINVALID": "-1", - "SPIDEV_1": "0", - "SPIDEV_2": "1", - "SPIDEV_3": "2", - "SPIDEV_4": "3" - }, - "Srxl2BindRequest": { - "_source": "inav/src/main/rx/srxl2_types.h", - "EnterBindMode": "235", - "RequestBindStatus": "181", - "BoundDataReport": "219", - "SetBindInfo": "91" - }, - "Srxl2BindType": { - "_source": "inav/src/main/rx/srxl2_types.h", - "NotBound": "0", - "DSM2_1024_22ms": "1", - "DSM2_1024_MC24": "2", - "DMS2_2048_11ms": "18", - "DMSX_22ms": "162", - "DMSX_11ms": "178", - "Surface_DSM2_16_5ms": "99", - "DSMR_11ms_22ms": "226", - "DSMR_5_5ms": "228" - }, - "Srxl2ControlDataCommand": { - "_source": "inav/src/main/rx/srxl2_types.h", - "ChannelData": "0", - "FailsafeChannelData": "1", - "VTXData": "2" - }, - "Srxl2DeviceId": { - "_source": "inav/src/main/rx/srxl2_types.h", - "FlightControllerDefault": "48", - "FlightControllerMax": "63", - "Broadcast": "255" - }, - "Srxl2DeviceType": { - "_source": "inav/src/main/rx/srxl2_types.h", - "NoDevice": "0", - "RemoteReceiver": "1", - "Receiver": "2", - "FlightController": "3", - "ESC": "4", - "Reserved": "5", - "SRXLServo": "6", - "SRXLServo_2": "7", - "VTX": "8" - }, - "Srxl2PacketType": { - "_source": "inav/src/main/rx/srxl2_types.h", - "Handshake": "33", - "BindInfo": "65", - "ParameterConfiguration": "80", - "SignalQuality": "85", - "TelemetrySensorData": "128", - "ControlData": "205" - }, - "Srxl2State": { - "_source": "inav/src/main/rx/srxl2_types.h", - "Disabled": "0", - "ListenForActivity": "1", - "SendHandshake": "2", - "ListenForHandshake": "3", - "Running": "4" - }, - "stateFlags_t": { - "_source": "inav/src/main/fc/runtime_config.h", - "GPS_FIX_HOME": "(1 << 0)", - "GPS_FIX": "(1 << 1)", - "CALIBRATE_MAG": "(1 << 2)", - "SMALL_ANGLE": "(1 << 3)", - "FIXED_WING_LEGACY": "(1 << 4)", - "ANTI_WINDUP": "(1 << 5)", - "FLAPERON_AVAILABLE": "(1 << 6)", - "NAV_MOTOR_STOP_OR_IDLE": "(1 << 7)", - "COMPASS_CALIBRATED": "(1 << 8)", - "ACCELEROMETER_CALIBRATED": "(1 << 9)", - "GPS_ESTIMATED_FIX": [ - "(1 << 10)", - "USE_GPS_FIX_ESTIMATION" - ], - "NAV_CRUISE_BRAKING": "(1 << 11)", - "NAV_CRUISE_BRAKING_BOOST": "(1 << 12)", - "NAV_CRUISE_BRAKING_LOCKED": "(1 << 13)", - "NAV_EXTRA_ARMING_SAFETY_BYPASSED": "(1 << 14)", - "AIRMODE_ACTIVE": "(1 << 15)", - "ESC_SENSOR_ENABLED": "(1 << 16)", - "AIRPLANE": "(1 << 17)", - "MULTIROTOR": "(1 << 18)", - "ROVER": "(1 << 19)", - "BOAT": "(1 << 20)", - "ALTITUDE_CONTROL": "(1 << 21)", - "MOVE_FORWARD_ONLY": "(1 << 22)", - "SET_REVERSIBLE_MOTORS_FORWARD": "(1 << 23)", - "FW_HEADING_USE_YAW": "(1 << 24)", - "ANTI_WINDUP_DEACTIVATED": "(1 << 25)", - "LANDING_DETECTED": "(1 << 26)", - "IN_FLIGHT_EMERG_REARM": "(1 << 27)", - "TAILSITTER": "(1 << 28)" - }, - "stickPositions_e": { - "_source": "inav/src/main/fc/rc_controls.h", - "ROL_LO": "(1 << (2 * ROLL))", - "ROL_CE": "(3 << (2 * ROLL))", - "ROL_HI": "(2 << (2 * ROLL))", - "PIT_LO": "(1 << (2 * PITCH))", - "PIT_CE": "(3 << (2 * PITCH))", - "PIT_HI": "(2 << (2 * PITCH))", - "YAW_LO": "(1 << (2 * YAW))", - "YAW_CE": "(3 << (2 * YAW))", - "YAW_HI": "(2 << (2 * YAW))", - "THR_LO": "(1 << (2 * THROTTLE))", - "THR_CE": "(3 << (2 * THROTTLE))", - "THR_HI": "(2 << (2 * THROTTLE))" - }, - "systemState_e": { - "_source": "inav/src/main/fc/fc_init.h", - "SYSTEM_STATE_INITIALISING": "0", - "SYSTEM_STATE_CONFIG_LOADED": "(1 << 0)", - "SYSTEM_STATE_SENSORS_READY": "(1 << 1)", - "SYSTEM_STATE_MOTORS_READY": "(1 << 2)", - "SYSTEM_STATE_TRANSPONDER_ENABLED": "(1 << 3)", - "SYSTEM_STATE_READY": "(1 << 7)" - }, - "tchDmaState_e": { - "_source": "inav/src/main/drivers/timer.h", - "TCH_DMA_IDLE": "0", - "TCH_DMA_READY": "1", - "TCH_DMA_ACTIVE": "2" - }, - "tempSensorType_e": { - "_source": "inav/src/main/sensors/temperature.h", - "TEMP_SENSOR_NONE": "0", - "TEMP_SENSOR_LM75": "1", - "TEMP_SENSOR_DS18B20": "2" - }, - "throttleStatus_e": { - "_source": "inav/src/main/fc/rc_controls.h", - "THROTTLE_LOW": "0", - "THROTTLE_HIGH": "1" - }, - "throttleStatusType_e": { - "_source": "inav/src/main/fc/rc_controls.h", - "THROTTLE_STATUS_TYPE_RC": "0", - "THROTTLE_STATUS_TYPE_COMMAND": "1" - }, - "timerMode_e": { - "_source": "inav/src/main/drivers/serial_softserial.c", - "TIMER_MODE_SINGLE": "0", - "TIMER_MODE_DUAL": "1" - }, - "timerUsageFlag_e": { - "_source": "inav/src/main/drivers/timer.h", - "TIM_USE_ANY": "0", - "TIM_USE_PPM": "(1 << 0)", - "TIM_USE_PWM": "(1 << 1)", - "TIM_USE_MOTOR": "(1 << 2)", - "TIM_USE_SERVO": "(1 << 3)", - "TIM_USE_MC_CHNFW": "(1 << 4)", - "TIM_USE_LED": "(1 << 24)", - "TIM_USE_BEEPER": "(1 << 25)" - }, - "timId_e": { - "_source": "inav/src/main/io/ledstrip.c", - "timBlink": "0", - "timLarson": "1", - "timBattery": "2", - "timRssi": "3", - "timGps": [ - "(4)", - "USE_GPS" - ], - "timWarning": "5", - "timIndicator": "6", - "timAnimation": [ - "(7)", - "USE_LED_ANIMATION" - ], - "timRing": "8", - "timTimerCount": "9" - }, - "tristate_e": { - "_source": "inav/src/main/common/tristate.h", - "TRISTATE_AUTO": "0", - "TRISTATE_ON": "1", - "TRISTATE_OFF": "2" - }, - "tz_automatic_dst_e": { - "_source": "inav/src/main/common/time.h", - "TZ_AUTO_DST_OFF": "0", - "TZ_AUTO_DST_EU": "1", - "TZ_AUTO_DST_USA": "2" - }, - "UARTDevice_e": { - "_source": "inav/src/main/drivers/serial_uart.h", - "UARTDEV_1": "0", - "UARTDEV_2": "1", - "UARTDEV_3": "2", - "UARTDEV_4": "3", - "UARTDEV_5": "4", - "UARTDEV_6": "5", - "UARTDEV_7": "6", - "UARTDEV_8": "7", - "UARTDEV_MAX": "8" - }, - "uartInverterLine_e": { - "_source": "inav/src/main/drivers/uart_inverter.h", - "UART_INVERTER_LINE_NONE": "0", - "UART_INVERTER_LINE_RX": "1 << 0", - "UART_INVERTER_LINE_TX": "1 << 1" - }, - "ublox_nav_sig_health_e": { - "_source": "inav/src/main/io/gps_ublox.h", - "UBLOX_SIG_HEALTH_UNKNOWN": "0", - "UBLOX_SIG_HEALTH_HEALTHY": "1", - "UBLOX_SIG_HEALTH_UNHEALTHY": "2" - }, - "ublox_nav_sig_quality": { - "_source": "inav/src/main/io/gps_ublox.h", - "UBLOX_SIG_QUALITY_NOSIGNAL": "0", - "UBLOX_SIG_QUALITY_SEARCHING": "1", - "UBLOX_SIG_QUALITY_ACQUIRED": "2", - "UBLOX_SIG_QUALITY_UNUSABLE": "3", - "UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC": "4", - "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC": "5", - "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2": "6", - "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3": "7" - }, - "ubs_nav_fix_type_t": { - "_source": "inav/src/main/io/gps_ublox.h", - "FIX_NONE": "0", - "FIX_DEAD_RECKONING": "1", - "FIX_2D": "2", - "FIX_3D": "3", - "FIX_GPS_DEAD_RECKONING": "4", - "FIX_TIME": "5" - }, - "ubx_ack_state_t": { - "_source": "inav/src/main/io/gps_ublox.h", - "UBX_ACK_WAITING": "0", - "UBX_ACK_GOT_ACK": "1", - "UBX_ACK_GOT_NAK": "2" - }, - "ubx_nav_status_bits_t": { - "_source": "inav/src/main/io/gps_ublox.h", - "NAV_STATUS_FIX_VALID": "1" - }, - "ubx_protocol_bytes_t": { - "_source": "inav/src/main/io/gps_ublox.h", - "PREAMBLE1": "181", - "PREAMBLE2": "98", - "CLASS_NAV": "1", - "CLASS_ACK": "5", - "CLASS_CFG": "6", - "CLASS_MON": "10", - "MSG_CLASS_UBX": "1", - "MSG_CLASS_NMEA": "240", - "MSG_VER": "4", - "MSG_ACK_NACK": "0", - "MSG_ACK_ACK": "1", - "MSG_NMEA_GGA": "0", - "MSG_NMEA_GLL": "1", - "MSG_NMEA_GSA": "2", - "MSG_NMEA_GSV": "3", - "MSG_NMEA_RMC": "4", - "MSG_NMEA_VGS": "5", - "MSG_POSLLH": "2", - "MSG_STATUS": "3", - "MSG_SOL": "6", - "MSG_PVT": "7", - "MSG_VELNED": "18", - "MSG_TIMEUTC": "33", - "MSG_SVINFO": "48", - "MSG_NAV_SAT": "53", - "MSG_CFG_PRT": "0", - "MSG_CFG_RATE": "8", - "MSG_CFG_SET_RATE": "1", - "MSG_CFG_NAV_SETTINGS": "36", - "MSG_CFG_SBAS": "22", - "MSG_CFG_GNSS": "62", - "MSG_MON_GNSS": "40", - "MSG_NAV_SIG": "67" - }, - "vcselPeriodType_e": { - "_source": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c", - "VcselPeriodPreRange": "0", - "VcselPeriodFinalRange": "1" - }, - "videoSystem_e": { - "_source": "inav/src/main/drivers/osd.h", - "VIDEO_SYSTEM_AUTO": "0", - "VIDEO_SYSTEM_PAL": "1", - "VIDEO_SYSTEM_NTSC": "2", - "VIDEO_SYSTEM_HDZERO": "3", - "VIDEO_SYSTEM_DJIWTF": "4", - "VIDEO_SYSTEM_AVATAR": "5", - "VIDEO_SYSTEM_DJICOMPAT": "6", - "VIDEO_SYSTEM_DJICOMPAT_HD": "7", - "VIDEO_SYSTEM_DJI_NATIVE": "8" - }, - "voltageSensor_e": { - "_source": "inav/src/main/sensors/battery_config_structs.h", - "VOLTAGE_SENSOR_NONE": "0", - "VOLTAGE_SENSOR_ADC": "1", - "VOLTAGE_SENSOR_ESC": "2", - "VOLTAGE_SENSOR_FAKE": "3", - "VOLTAGE_SENSOR_SMARTPORT": "4", - "VOLTAGE_SENSOR_MAX": "VOLTAGE_SENSOR_SMARTPORT" - }, - "vs600Band_e": { - "_source": "inav/src/main/io/smartport_master.h", - "VS600_BAND_A": "0", - "VS600_BAND_B": "1", - "VS600_BAND_C": "2", - "VS600_BAND_D": "3", - "VS600_BAND_E": "4", - "VS600_BAND_F": "5" - }, - "vs600Power_e": { - "_source": "inav/src/main/io/smartport_master.h", - "VS600_POWER_PIT": "0", - "VS600_POWER_25MW": "1", - "VS600_POWER_200MW": "2", - "VS600_POWER_600MW": "3" - }, - "vtxDevType_e": { - "_source": "inav/src/main/drivers/vtx_common.h", - "VTXDEV_UNSUPPORTED": "0", - "VTXDEV_RTC6705": "1", - "VTXDEV_SMARTAUDIO": "3", - "VTXDEV_TRAMP": "4", - "VTXDEV_FFPV": "5", - "VTXDEV_MSP": "6", - "VTXDEV_UNKNOWN": "255" - }, - "vtxFrequencyGroups_e": { - "_source": "inav/src/main/drivers/vtx_common.h", - "FREQUENCYGROUP_5G8": "0", - "FREQUENCYGROUP_2G4": "1", - "FREQUENCYGROUP_1G3": "2" - }, - "vtxLowerPowerDisarm_e": { - "_source": "inav/src/main/io/vtx.h", - "VTX_LOW_POWER_DISARM_OFF": "0", - "VTX_LOW_POWER_DISARM_ALWAYS": "1", - "VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM": "2" - }, - "vtxProtoResponseType_e": { - "_source": "inav/src/main/io/vtx_tramp.c", - "VTX_RESPONSE_TYPE_NONE": "0", - "VTX_RESPONSE_TYPE_CAPABILITIES": "1", - "VTX_RESPONSE_TYPE_STATUS": "2" - }, - "vtxProtoState_e": { - "_source": "inav/src/main/io/vtx_tramp.c", - "VTX_STATE_RESET": "0", - "VTX_STATE_OFFILE": "1", - "VTX_STATE_DETECTING": "2", - "VTX_STATE_IDLE": "3", - "VTX_STATE_QUERY_DELAY": "4", - "VTX_STATE_QUERY_STATUS": "5", - "VTX_STATE_WAIT_STATUS": "6" - }, - "vtxScheduleParams_e": { - "_source": "inav/src/main/io/vtx.c", - "VTX_PARAM_POWER": "0", - "VTX_PARAM_BANDCHAN": "1", - "VTX_PARAM_PITMODE": "2", - "VTX_PARAM_COUNT": "3" - }, - "warningFlags_e": { - "_source": "inav/src/main/io/ledstrip.c", - "WARNING_ARMING_DISABLED": "0", - "WARNING_LOW_BATTERY": "1", - "WARNING_FAILSAFE": "2", - "WARNING_HW_ERROR": "3" - }, - "warningLedState_e": { - "_source": "inav/src/main/io/statusindicator.c", - "WARNING_LED_OFF": "0", - "WARNING_LED_ON": "1", - "WARNING_LED_FLASH": "2" - }, - "widgetAHIOptions_t": { - "_source": "inav/src/main/drivers/display_widgets.h", - "DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS": "1 << 0" - }, - "widgetAHIStyle_e": { - "_source": "inav/src/main/drivers/display_widgets.h", - "DISPLAY_WIDGET_AHI_STYLE_STAIRCASE": "0", - "DISPLAY_WIDGET_AHI_STYLE_LINE": "1" - }, - "wpFwTurnSmoothing_e": { - "_source": "inav/src/main/navigation/navigation.h", - "WP_TURN_SMOOTHING_OFF": "0", - "WP_TURN_SMOOTHING_ON": "1", - "WP_TURN_SMOOTHING_CUT": "2" - }, - "wpMissionPlannerStatus_e": { - "_source": "inav/src/main/navigation/navigation.h", - "WP_PLAN_WAIT": "0", - "WP_PLAN_SAVE": "1", - "WP_PLAN_OK": "2", - "WP_PLAN_FULL": "3" - }, - "zeroCalibrationState_e": { - "_source": "inav/src/main/common/calibration.h", - "ZERO_CALIBRATION_NONE": "0", - "ZERO_CALIBRATION_IN_PROGRESS": "1", - "ZERO_CALIBRATION_DONE": "2", - "ZERO_CALIBRATION_FAIL": "3" + "build": { + "fc_version": { + "major": 9, + "minor": 0, + "patch": 0 + }, + "git_revision": "86dc81ba" + }, + "enums": { + "accelerationSensor_e": { + "_source": "inav/src/main/sensors/acceleration.h", + "ACC_NONE": "0", + "ACC_AUTODETECT": "1", + "ACC_MPU6000": "2", + "ACC_MPU6500": "3", + "ACC_MPU9250": "4", + "ACC_BMI160": "5", + "ACC_ICM20689": "6", + "ACC_BMI088": "7", + "ACC_ICM42605": "8", + "ACC_BMI270": "9", + "ACC_LSM6DXX": "10", + "ACC_FAKE": "11", + "ACC_MAX": "ACC_FAKE" + }, + "accEvent_t": { + "_source": "inav/src/main/telemetry/sim.c", + "ACC_EVENT_NONE": "0", + "ACC_EVENT_HIGH": "1", + "ACC_EVENT_LOW": "2", + "ACC_EVENT_NEG_X": "3" + }, + "adcChannel_e": { + "_source": "inav/src/main/drivers/adc.h", + "ADC_CHN_NONE": "0", + "ADC_CHN_1": "1", + "ADC_CHN_2": "2", + "ADC_CHN_3": "3", + "ADC_CHN_4": "4", + "ADC_CHN_5": "5", + "ADC_CHN_6": "6", + "ADC_CHN_MAX": "ADC_CHN_6", + "ADC_CHN_COUNT": "" + }, + "ADCDevice": { + "_source": "inav/src/main/drivers/adc_impl.h", + "ADCINVALID": "-1", + "ADCDEV_1": "0", + "ADCDEV_2": [ + "(1)", + "STM32F4 || STM32F7 || STM32H7" + ], + "ADCDEV_3": [ + "(2)", + "STM32F4 || STM32F7 || STM32H7" + ], + "ADCDEV_MAX": [ + "ADCDEV_1", + "NOT(STM32F4 || STM32F7 || STM32H7)" + ], + "ADCDEV_COUNT": "ADCDEV_MAX + 1" + }, + "adcFunction_e": { + "_source": "inav/src/main/drivers/adc.h", + "ADC_BATTERY": "0", + "ADC_RSSI": "1", + "ADC_CURRENT": "2", + "ADC_AIRSPEED": "3", + "ADC_FUNCTION_COUNT": "4" + }, + "adjustmentFunction_e": { + "_source": "inav/src/main/fc/rc_adjustments.h", + "ADJUSTMENT_NONE": "0", + "ADJUSTMENT_RC_RATE": "1", + "ADJUSTMENT_RC_EXPO": "2", + "ADJUSTMENT_THROTTLE_EXPO": "3", + "ADJUSTMENT_PITCH_ROLL_RATE": "4", + "ADJUSTMENT_YAW_RATE": "5", + "ADJUSTMENT_PITCH_ROLL_P": "6", + "ADJUSTMENT_PITCH_ROLL_I": "7", + "ADJUSTMENT_PITCH_ROLL_D": "8", + "ADJUSTMENT_PITCH_ROLL_FF": "9", + "ADJUSTMENT_PITCH_P": "10", + "ADJUSTMENT_PITCH_I": "11", + "ADJUSTMENT_PITCH_D": "12", + "ADJUSTMENT_PITCH_FF": "13", + "ADJUSTMENT_ROLL_P": "14", + "ADJUSTMENT_ROLL_I": "15", + "ADJUSTMENT_ROLL_D": "16", + "ADJUSTMENT_ROLL_FF": "17", + "ADJUSTMENT_YAW_P": "18", + "ADJUSTMENT_YAW_I": "19", + "ADJUSTMENT_YAW_D": "20", + "ADJUSTMENT_YAW_FF": "21", + "ADJUSTMENT_RATE_PROFILE": "22", + "ADJUSTMENT_PITCH_RATE": "23", + "ADJUSTMENT_ROLL_RATE": "24", + "ADJUSTMENT_RC_YAW_EXPO": "25", + "ADJUSTMENT_MANUAL_RC_EXPO": "26", + "ADJUSTMENT_MANUAL_RC_YAW_EXPO": "27", + "ADJUSTMENT_MANUAL_PITCH_ROLL_RATE": "28", + "ADJUSTMENT_MANUAL_ROLL_RATE": "29", + "ADJUSTMENT_MANUAL_PITCH_RATE": "30", + "ADJUSTMENT_MANUAL_YAW_RATE": "31", + "ADJUSTMENT_NAV_FW_CRUISE_THR": "32", + "ADJUSTMENT_NAV_FW_PITCH2THR": "33", + "ADJUSTMENT_ROLL_BOARD_ALIGNMENT": "34", + "ADJUSTMENT_PITCH_BOARD_ALIGNMENT": "35", + "ADJUSTMENT_LEVEL_P": "36", + "ADJUSTMENT_LEVEL_I": "37", + "ADJUSTMENT_LEVEL_D": "38", + "ADJUSTMENT_POS_XY_P": "39", + "ADJUSTMENT_POS_XY_I": "40", + "ADJUSTMENT_POS_XY_D": "41", + "ADJUSTMENT_POS_Z_P": "42", + "ADJUSTMENT_POS_Z_I": "43", + "ADJUSTMENT_POS_Z_D": "44", + "ADJUSTMENT_HEADING_P": "45", + "ADJUSTMENT_VEL_XY_P": "46", + "ADJUSTMENT_VEL_XY_I": "47", + "ADJUSTMENT_VEL_XY_D": "48", + "ADJUSTMENT_VEL_Z_P": "49", + "ADJUSTMENT_VEL_Z_I": "50", + "ADJUSTMENT_VEL_Z_D": "51", + "ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "52", + "ADJUSTMENT_VTX_POWER_LEVEL": "53", + "ADJUSTMENT_TPA": "54", + "ADJUSTMENT_TPA_BREAKPOINT": "55", + "ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS": "56", + "ADJUSTMENT_FW_TPA_TIME_CONSTANT": "57", + "ADJUSTMENT_FW_LEVEL_TRIM": "58", + "ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX": "59", + "ADJUSTMENT_NAV_FW_ALT_CONTROL_RESPONSE": "60", + "ADJUSTMENT_FUNCTION_COUNT": "61" + }, + "adjustmentMode_e": { + "_source": "inav/src/main/fc/rc_adjustments.h", + "ADJUSTMENT_MODE_STEP": "0", + "ADJUSTMENT_MODE_SELECT": "1" + }, + "afatfsAppendFreeClusterPhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_INITIAL": "0", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_FIND_FREESPACE": "0", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT1": "1", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT2": "2", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_COMPLETE": "4", + "AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE": "5" + }, + "afatfsAppendSuperclusterPhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_APPEND_SUPERCLUSTER_PHASE_INIT": "0", + "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FREEFILE_DIRECTORY": "1", + "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FAT": "2", + "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3" + }, + "afatfsCacheBlockState_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_CACHE_STATE_EMPTY": "0", + "AFATFS_CACHE_STATE_IN_SYNC": "1", + "AFATFS_CACHE_STATE_READING": "2", + "AFATFS_CACHE_STATE_WRITING": "3", + "AFATFS_CACHE_STATE_DIRTY": "4" + }, + "afatfsClusterSearchCondition_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "CLUSTER_SEARCH_FREE_AT_BEGINNING_OF_FAT_SECTOR": "0", + "CLUSTER_SEARCH_FREE": "1", + "CLUSTER_SEARCH_OCCUPIED": "2" + }, + "afatfsDeleteFilePhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY": "0", + "AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS": "1" + }, + "afatfsError_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", + "AFATFS_ERROR_NONE": "0", + "AFATFS_ERROR_GENERIC": "1", + "AFATFS_ERROR_BAD_MBR": "2", + "AFATFS_ERROR_BAD_FILESYSTEM_HEADER": "3" + }, + "afatfsExtendSubdirectoryPhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_EXTEND_SUBDIRECTORY_PHASE_INITIAL": "0", + "AFATFS_EXTEND_SUBDIRECTORY_PHASE_ADD_FREE_CLUSTER": "0", + "AFATFS_EXTEND_SUBDIRECTORY_PHASE_WRITE_SECTORS": "1", + "AFATFS_EXTEND_SUBDIRECTORY_PHASE_SUCCESS": "2", + "AFATFS_EXTEND_SUBDIRECTORY_PHASE_FAILURE": "3" + }, + "afatfsFATPattern_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_FAT_PATTERN_UNTERMINATED_CHAIN": "0", + "AFATFS_FAT_PATTERN_TERMINATED_CHAIN": "1", + "AFATFS_FAT_PATTERN_FREE": "2" + }, + "afatfsFileOperation_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_FILE_OPERATION_NONE": "0", + "AFATFS_FILE_OPERATION_CREATE_FILE": "1", + "AFATFS_FILE_OPERATION_SEEK": "2", + "AFATFS_FILE_OPERATION_CLOSE": "3", + "AFATFS_FILE_OPERATION_TRUNCATE": "4", + "AFATFS_FILE_OPERATION_UNLINK": "5", + "AFATFS_FILE_OPERATION_APPEND_SUPERCLUSTER": [ + "(6)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_FILE_OPERATION_LOCKED": [ + "(7)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_FILE_OPERATION_APPEND_FREE_CLUSTER": "8", + "AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY": "9" + }, + "afatfsFilesystemState_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", + "AFATFS_FILESYSTEM_STATE_UNKNOWN": "0", + "AFATFS_FILESYSTEM_STATE_FATAL": "1", + "AFATFS_FILESYSTEM_STATE_INITIALIZATION": "2", + "AFATFS_FILESYSTEM_STATE_READY": "3" + }, + "afatfsFileType_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_FILE_TYPE_NONE": "0", + "AFATFS_FILE_TYPE_NORMAL": "1", + "AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY": "2", + "AFATFS_FILE_TYPE_DIRECTORY": "3" + }, + "afatfsFindClusterStatus_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_FIND_CLUSTER_IN_PROGRESS": "0", + "AFATFS_FIND_CLUSTER_FOUND": "1", + "AFATFS_FIND_CLUSTER_FATAL": "2", + "AFATFS_FIND_CLUSTER_NOT_FOUND": "3" + }, + "afatfsFreeSpaceSearchPhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_FREE_SPACE_SEARCH_PHASE_FIND_HOLE": "0", + "AFATFS_FREE_SPACE_SEARCH_PHASE_GROW_HOLE": "1" + }, + "afatfsInitializationPhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_INITIALIZATION_READ_MBR": "0", + "AFATFS_INITIALIZATION_READ_VOLUME_ID": "1", + "AFATFS_INITIALIZATION_FREEFILE_CREATE": [ + "(2)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_INITIALIZATION_FREEFILE_CREATING": [ + "(3)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_INITIALIZATION_FREEFILE_FAT_SEARCH": [ + "(4)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_INITIALIZATION_FREEFILE_UPDATE_FAT": [ + "(5)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY": [ + "(6)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_INITIALIZATION_FREEFILE_LAST": [ + "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_INITIALIZATION_DONE": "" + }, + "afatfsOperationStatus_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", + "AFATFS_OPERATION_IN_PROGRESS": "0", + "AFATFS_OPERATION_SUCCESS": "1", + "AFATFS_OPERATION_FAILURE": "2" + }, + "afatfsSaveDirectoryEntryMode_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_SAVE_DIRECTORY_NORMAL": "0", + "AFATFS_SAVE_DIRECTORY_FOR_CLOSE": "1", + "AFATFS_SAVE_DIRECTORY_DELETED": "2" + }, + "afatfsSeek_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.h", + "AFATFS_SEEK_SET": "0", + "AFATFS_SEEK_CUR": "1", + "AFATFS_SEEK_END": "2" + }, + "afatfsTruncateFilePhase_e": { + "_source": "inav/src/main/io/asyncfatfs/asyncfatfs.c", + "AFATFS_TRUNCATE_FILE_INITIAL": "0", + "AFATFS_TRUNCATE_FILE_UPDATE_DIRECTORY": "0", + "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_NORMAL": "1", + "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_CONTIGUOUS": [ + "(2)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_TRUNCATE_FILE_PREPEND_TO_FREEFILE": [ + "(3)", + "AFATFS_USE_FREEFILE" + ], + "AFATFS_TRUNCATE_FILE_SUCCESS": "4" + }, + "airmodeHandlingType_e": { + "_source": "inav/src/main/fc/rc_controls.h", + "STICK_CENTER": "0", + "THROTTLE_THRESHOLD": "1", + "STICK_CENTER_ONCE": "2" + }, + "angle_index_t": { + "_source": "inav/src/main/common/axis.h", + "AI_ROLL": "0", + "AI_PITCH": "1" + }, + "armingFlag_e": { + "_source": "inav/src/main/fc/runtime_config.h", + "ARMED": "(1 << 2)", + "WAS_EVER_ARMED": "(1 << 3)", + "SIMULATOR_MODE_HITL": "(1 << 4)", + "SIMULATOR_MODE_SITL": "(1 << 5)", + "ARMING_DISABLED_GEOZONE": "(1 << 6)", + "ARMING_DISABLED_FAILSAFE_SYSTEM": "(1 << 7)", + "ARMING_DISABLED_NOT_LEVEL": "(1 << 8)", + "ARMING_DISABLED_SENSORS_CALIBRATING": "(1 << 9)", + "ARMING_DISABLED_SYSTEM_OVERLOADED": "(1 << 10)", + "ARMING_DISABLED_NAVIGATION_UNSAFE": "(1 << 11)", + "ARMING_DISABLED_COMPASS_NOT_CALIBRATED": "(1 << 12)", + "ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED": "(1 << 13)", + "ARMING_DISABLED_ARM_SWITCH": "(1 << 14)", + "ARMING_DISABLED_HARDWARE_FAILURE": "(1 << 15)", + "ARMING_DISABLED_BOXFAILSAFE": "(1 << 16)", + "ARMING_DISABLED_RC_LINK": "(1 << 18)", + "ARMING_DISABLED_THROTTLE": "(1 << 19)", + "ARMING_DISABLED_CLI": "(1 << 20)", + "ARMING_DISABLED_CMS_MENU": "(1 << 21)", + "ARMING_DISABLED_OSD_MENU": "(1 << 22)", + "ARMING_DISABLED_ROLLPITCH_NOT_CENTERED": "(1 << 23)", + "ARMING_DISABLED_SERVO_AUTOTRIM": "(1 << 24)", + "ARMING_DISABLED_OOM": "(1 << 25)", + "ARMING_DISABLED_INVALID_SETTING": "(1 << 26)", + "ARMING_DISABLED_PWM_OUTPUT_ERROR": "(1 << 27)", + "ARMING_DISABLED_NO_PREARM": "(1 << 28)", + "ARMING_DISABLED_DSHOT_BEEPER": "(1 << 29)", + "ARMING_DISABLED_LANDING_DETECTED": "(1 << 30)", + "ARMING_DISABLED_ALL_FLAGS": "(ARMING_DISABLED_GEOZONE | ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED | ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING | ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER | ARMING_DISABLED_LANDING_DETECTED)" + }, + "axis_e": { + "_source": "inav/src/main/common/axis.h", + "X": "0", + "Y": "1", + "Z": "2" + }, + "barometerState_e": { + "_source": "inav/src/main/sensors/barometer.c", + "BAROMETER_NEEDS_SAMPLES": "0", + "BAROMETER_NEEDS_CALCULATION": "1" + }, + "baroSensor_e": { + "_source": "inav/src/main/sensors/barometer.h", + "BARO_NONE": "0", + "BARO_AUTODETECT": "1", + "BARO_BMP085": "2", + "BARO_MS5611": "3", + "BARO_BMP280": "4", + "BARO_MS5607": "5", + "BARO_LPS25H": "6", + "BARO_SPL06": "7", + "BARO_BMP388": "8", + "BARO_DPS310": "9", + "BARO_B2SMPB": "10", + "BARO_MSP": "11", + "BARO_FAKE": "12", + "BARO_MAX": "BARO_FAKE" + }, + "batCapacityUnit_e": { + "_source": "inav/src/main/sensors/battery_config_structs.h", + "BAT_CAPACITY_UNIT_MAH": "0", + "BAT_CAPACITY_UNIT_MWH": "1" + }, + "batteryState_e": { + "_source": "inav/src/main/sensors/battery.h", + "BATTERY_OK": "0", + "BATTERY_WARNING": "1", + "BATTERY_CRITICAL": "2", + "BATTERY_NOT_PRESENT": "3" + }, + "batVoltageSource_e": { + "_source": "inav/src/main/sensors/battery_config_structs.h", + "BAT_VOLTAGE_RAW": "0", + "BAT_VOLTAGE_SAG_COMP": "1" + }, + "baudRate_e": { + "_source": "inav/src/main/io/serial.h", + "BAUD_AUTO": "0", + "BAUD_1200": "1", + "BAUD_2400": "2", + "BAUD_4800": "3", + "BAUD_9600": "4", + "BAUD_19200": "5", + "BAUD_38400": "6", + "BAUD_57600": "7", + "BAUD_115200": "8", + "BAUD_230400": "9", + "BAUD_250000": "10", + "BAUD_460800": "11", + "BAUD_921600": "12", + "BAUD_1000000": "13", + "BAUD_1500000": "14", + "BAUD_2000000": "15", + "BAUD_2470000": "16", + "BAUD_MIN": "BAUD_AUTO", + "BAUD_MAX": "BAUD_2470000" + }, + "beeperMode_e": { + "_source": "inav/src/main/io/beeper.h", + "BEEPER_SILENCE": "0", + "BEEPER_RUNTIME_CALIBRATION_DONE": "1", + "BEEPER_HARDWARE_FAILURE": "2", + "BEEPER_RX_LOST": "3", + "BEEPER_RX_LOST_LANDING": "4", + "BEEPER_DISARMING": "5", + "BEEPER_ARMING": "6", + "BEEPER_ARMING_GPS_FIX": "7", + "BEEPER_BAT_CRIT_LOW": "8", + "BEEPER_BAT_LOW": "9", + "BEEPER_GPS_STATUS": "10", + "BEEPER_RX_SET": "11", + "BEEPER_ACTION_SUCCESS": "12", + "BEEPER_ACTION_FAIL": "13", + "BEEPER_READY_BEEP": "14", + "BEEPER_MULTI_BEEPS": "15", + "BEEPER_DISARM_REPEAT": "16", + "BEEPER_ARMED": "17", + "BEEPER_SYSTEM_INIT": "18", + "BEEPER_USB": "19", + "BEEPER_LAUNCH_MODE_ENABLED": "20", + "BEEPER_LAUNCH_MODE_LOW_THROTTLE": "21", + "BEEPER_LAUNCH_MODE_IDLE_START": "22", + "BEEPER_CAM_CONNECTION_OPEN": "23", + "BEEPER_CAM_CONNECTION_CLOSE": "24", + "BEEPER_ALL": "25", + "BEEPER_PREFERENCE": "26" + }, + "biquadFilterType_e": { + "_source": "inav/src/main/common/filter.h", + "FILTER_LPF": "0", + "FILTER_NOTCH": "1" + }, + "blackboxBufferReserveStatus_e": { + "_source": "inav/src/main/blackbox/blackbox_io.h", + "BLACKBOX_RESERVE_SUCCESS": "0", + "BLACKBOX_RESERVE_TEMPORARY_FAILURE": "1", + "BLACKBOX_RESERVE_PERMANENT_FAILURE": "2" + }, + "BlackboxDevice": { + "_source": "inav/src/main/blackbox/blackbox_io.h", + "BLACKBOX_DEVICE_SERIAL": "0", + "BLACKBOX_DEVICE_FLASH": [ + "1", + "USE_FLASHFS" + ], + "BLACKBOX_DEVICE_SDCARD": [ + "2", + "USE_SDCARD" + ], + "BLACKBOX_DEVICE_FILE": [ + "3", + "SITL_BUILD" + ], + "BLACKBOX_DEVICE_END": "4" + }, + "blackboxFeatureMask_e": { + "_source": "inav/src/main/blackbox/blackbox.h", + "BLACKBOX_FEATURE_NAV_ACC": "1 << 0", + "BLACKBOX_FEATURE_NAV_POS": "1 << 1", + "BLACKBOX_FEATURE_NAV_PID": "1 << 2", + "BLACKBOX_FEATURE_MAG": "1 << 3", + "BLACKBOX_FEATURE_ACC": "1 << 4", + "BLACKBOX_FEATURE_ATTITUDE": "1 << 5", + "BLACKBOX_FEATURE_RC_DATA": "1 << 6", + "BLACKBOX_FEATURE_RC_COMMAND": "1 << 7", + "BLACKBOX_FEATURE_MOTORS": "1 << 8", + "BLACKBOX_FEATURE_GYRO_RAW": "1 << 9", + "BLACKBOX_FEATURE_GYRO_PEAKS_ROLL": "1 << 10", + "BLACKBOX_FEATURE_GYRO_PEAKS_PITCH": "1 << 11", + "BLACKBOX_FEATURE_GYRO_PEAKS_YAW": "1 << 12", + "BLACKBOX_FEATURE_SERVOS": "1 << 13" + }, + "BlackboxState": { + "_source": "inav/src/main/blackbox/blackbox.h", + "BLACKBOX_STATE_DISABLED": "0", + "BLACKBOX_STATE_STOPPED": "1", + "BLACKBOX_STATE_PREPARE_LOG_FILE": "2", + "BLACKBOX_STATE_SEND_HEADER": "3", + "BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER": "4", + "BLACKBOX_STATE_SEND_GPS_H_HEADER": "5", + "BLACKBOX_STATE_SEND_GPS_G_HEADER": "6", + "BLACKBOX_STATE_SEND_SLOW_HEADER": "7", + "BLACKBOX_STATE_SEND_SYSINFO": "8", + "BLACKBOX_STATE_PAUSED": "9", + "BLACKBOX_STATE_RUNNING": "10", + "BLACKBOX_STATE_SHUTTING_DOWN": "11" + }, + "bmi270Register_e": { + "_source": "inav/src/main/drivers/accgyro/accgyro_bmi270.c", + "BMI270_REG_CHIP_ID": "0", + "BMI270_REG_ERR_REG": "2", + "BMI270_REG_STATUS": "3", + "BMI270_REG_ACC_DATA_X_LSB": "12", + "BMI270_REG_GYR_DATA_X_LSB": "18", + "BMI270_REG_SENSORTIME_0": "24", + "BMI270_REG_SENSORTIME_1": "25", + "BMI270_REG_SENSORTIME_2": "26", + "BMI270_REG_EVENT": "27", + "BMI270_REG_INT_STATUS_0": "28", + "BMI270_REG_INT_STATUS_1": "29", + "BMI270_REG_INTERNAL_STATUS": "33", + "BMI270_REG_TEMPERATURE_LSB": "34", + "BMI270_REG_TEMPERATURE_MSB": "35", + "BMI270_REG_FIFO_LENGTH_LSB": "36", + "BMI270_REG_FIFO_LENGTH_MSB": "37", + "BMI270_REG_FIFO_DATA": "38", + "BMI270_REG_ACC_CONF": "64", + "BMI270_REG_ACC_RANGE": "65", + "BMI270_REG_GYRO_CONF": "66", + "BMI270_REG_GYRO_RANGE": "67", + "BMI270_REG_AUX_CONF": "68", + "BMI270_REG_FIFO_DOWNS": "69", + "BMI270_REG_FIFO_WTM_0": "70", + "BMI270_REG_FIFO_WTM_1": "71", + "BMI270_REG_FIFO_CONFIG_0": "72", + "BMI270_REG_FIFO_CONFIG_1": "73", + "BMI270_REG_SATURATION": "74", + "BMI270_REG_INT1_IO_CTRL": "83", + "BMI270_REG_INT2_IO_CTRL": "84", + "BMI270_REG_INT_LATCH": "85", + "BMI270_REG_INT1_MAP_FEAT": "86", + "BMI270_REG_INT2_MAP_FEAT": "87", + "BMI270_REG_INT_MAP_DATA": "88", + "BMI270_REG_INIT_CTRL": "89", + "BMI270_REG_INIT_DATA": "94", + "BMI270_REG_ACC_SELF_TEST": "109", + "BMI270_REG_GYR_SELF_TEST_AXES": "110", + "BMI270_REG_PWR_CONF": "124", + "BMI270_REG_PWR_CTRL": "125", + "BMI270_REG_CMD": "126" + }, + "bootLogEventCode_e": { + "_source": "inav/src/main/drivers/logging_codes.h", + "BOOT_EVENT_CONFIG_LOADED": "0", + "BOOT_EVENT_SYSTEM_INIT_DONE": "1", + "BOOT_EVENT_PWM_INIT_DONE": "2", + "BOOT_EVENT_EXTRA_BOOT_DELAY": "3", + "BOOT_EVENT_SENSOR_INIT_DONE": "4", + "BOOT_EVENT_GPS_INIT_DONE": "5", + "BOOT_EVENT_LEDSTRIP_INIT_DONE": "6", + "BOOT_EVENT_TELEMETRY_INIT_DONE": "7", + "BOOT_EVENT_SYSTEM_READY": "8", + "BOOT_EVENT_GYRO_DETECTION": "9", + "BOOT_EVENT_ACC_DETECTION": "10", + "BOOT_EVENT_BARO_DETECTION": "11", + "BOOT_EVENT_MAG_DETECTION": "12", + "BOOT_EVENT_RANGEFINDER_DETECTION": "13", + "BOOT_EVENT_MAG_INIT_FAILED": "14", + "BOOT_EVENT_HMC5883L_READ_OK_COUNT": "15", + "BOOT_EVENT_HMC5883L_READ_FAILED": "16", + "BOOT_EVENT_HMC5883L_SATURATION": "17", + "BOOT_EVENT_TIMER_CH_SKIPPED": "18", + "BOOT_EVENT_TIMER_CH_MAPPED": "19", + "BOOT_EVENT_PITOT_DETECTION": "20", + "BOOT_EVENT_TEMP_SENSOR_DETECTION": "21", + "BOOT_EVENT_1WIRE_DETECTION": "22", + "BOOT_EVENT_HARDWARE_IO_CONFLICT": "23", + "BOOT_EVENT_OPFLOW_DETECTION": "24", + "BOOT_EVENT_CODE_COUNT": "25" + }, + "bootLogFlags_e": { + "_source": "inav/src/main/drivers/logging_codes.h", + "BOOT_EVENT_FLAGS_NONE": "0", + "BOOT_EVENT_FLAGS_WARNING": "1 << 0", + "BOOT_EVENT_FLAGS_ERROR": "1 << 1", + "BOOT_EVENT_FLAGS_PARAM16": "1 << 14", + "BOOT_EVENT_FLAGS_PARAM32": "1 << 15" + }, + "boxId_e": { + "_source": "inav/src/main/fc/rc_modes.h", + "BOXARM": "0", + "BOXANGLE": "1", + "BOXHORIZON": "2", + "BOXNAVALTHOLD": "3", + "BOXHEADINGHOLD": "4", + "BOXHEADFREE": "5", + "BOXHEADADJ": "6", + "BOXCAMSTAB": "7", + "BOXNAVRTH": "8", + "BOXNAVPOSHOLD": "9", + "BOXMANUAL": "10", + "BOXBEEPERON": "11", + "BOXLEDLOW": "12", + "BOXLIGHTS": "13", + "BOXNAVLAUNCH": "14", + "BOXOSD": "15", + "BOXTELEMETRY": "16", + "BOXBLACKBOX": "17", + "BOXFAILSAFE": "18", + "BOXNAVWP": "19", + "BOXAIRMODE": "20", + "BOXHOMERESET": "21", + "BOXGCSNAV": "22", + "BOXSURFACE": "24", + "BOXFLAPERON": "25", + "BOXTURNASSIST": "26", + "BOXAUTOTRIM": "27", + "BOXAUTOTUNE": "28", + "BOXCAMERA1": "29", + "BOXCAMERA2": "30", + "BOXCAMERA3": "31", + "BOXOSDALT1": "32", + "BOXOSDALT2": "33", + "BOXOSDALT3": "34", + "BOXNAVCOURSEHOLD": "35", + "BOXBRAKING": "36", + "BOXUSER1": "37", + "BOXUSER2": "38", + "BOXFPVANGLEMIX": "39", + "BOXLOITERDIRCHN": "40", + "BOXMSPRCOVERRIDE": "41", + "BOXPREARM": "42", + "BOXTURTLE": "43", + "BOXNAVCRUISE": "44", + "BOXAUTOLEVEL": "45", + "BOXPLANWPMISSION": "46", + "BOXSOARING": "47", + "BOXUSER3": "48", + "BOXUSER4": "49", + "BOXCHANGEMISSION": "50", + "BOXBEEPERMUTE": "51", + "BOXMULTIFUNCTION": "52", + "BOXMIXERPROFILE": "53", + "BOXMIXERTRANSITION": "54", + "BOXANGLEHOLD": "55", + "BOXGIMBALTLOCK": "56", + "BOXGIMBALRLOCK": "57", + "BOXGIMBALCENTER": "58", + "BOXGIMBALHTRK": "59", + "CHECKBOX_ITEM_COUNT": "60" + }, + "busIndex_e": { + "_source": "inav/src/main/drivers/bus.h", + "BUSINDEX_1": "0", + "BUSINDEX_2": "1", + "BUSINDEX_3": "2", + "BUSINDEX_4": "3" + }, + "busSpeed_e": { + "_source": "inav/src/main/drivers/bus.h", + "BUS_SPEED_INITIALIZATION": "0", + "BUS_SPEED_SLOW": "1", + "BUS_SPEED_STANDARD": "2", + "BUS_SPEED_FAST": "3", + "BUS_SPEED_ULTRAFAST": "4" + }, + "busType_e": { + "_source": "inav/src/main/drivers/bus.h", + "BUSTYPE_ANY": "0", + "BUSTYPE_NONE": "0", + "BUSTYPE_I2C": "1", + "BUSTYPE_SPI": "2", + "BUSTYPE_SDIO": "3" + }, + "channelType_t": { + "_source": "inav/src/main/drivers/timer.h", + "TYPE_FREE": "0", + "TYPE_PWMINPUT": "1", + "TYPE_PPMINPUT": "2", + "TYPE_PWMOUTPUT_MOTOR": "3", + "TYPE_PWMOUTPUT_FAST": "4", + "TYPE_PWMOUTPUT_SERVO": "5", + "TYPE_SOFTSERIAL_RX": "6", + "TYPE_SOFTSERIAL_TX": "7", + "TYPE_SOFTSERIAL_RXTX": "8", + "TYPE_SOFTSERIAL_AUXTIMER": "9", + "TYPE_ADC": "10", + "TYPE_SERIAL_RX": "11", + "TYPE_SERIAL_TX": "12", + "TYPE_SERIAL_RXTX": "13", + "TYPE_TIMER": "14" + }, + "climbRateToAltitudeControllerMode_e": { + "_source": "inav/src/main/navigation/navigation_private.h", + "ROC_TO_ALT_CURRENT": "0", + "ROC_TO_ALT_CONSTANT": "1", + "ROC_TO_ALT_TARGET": "2" + }, + "colorComponent_e": { + "_source": "inav/src/main/common/color.h", + "RGB_RED": "0", + "RGB_GREEN": "1", + "RGB_BLUE": "2" + }, + "colorId_e": { + "_source": "inav/src/main/io/ledstrip.h", + "COLOR_BLACK": "0", + "COLOR_WHITE": "1", + "COLOR_RED": "2", + "COLOR_ORANGE": "3", + "COLOR_YELLOW": "4", + "COLOR_LIME_GREEN": "5", + "COLOR_GREEN": "6", + "COLOR_MINT_GREEN": "7", + "COLOR_CYAN": "8", + "COLOR_LIGHT_BLUE": "9", + "COLOR_BLUE": "10", + "COLOR_DARK_VIOLET": "11", + "COLOR_MAGENTA": "12", + "COLOR_DEEP_PINK": "13" + }, + "crsfActiveAntenna_e": { + "_source": "inav/src/main/telemetry/crsf.c", + "CRSF_ACTIVE_ANTENNA1": "0", + "CRSF_ACTIVE_ANTENNA2": "1" + }, + "crsfAddress_e": { + "_source": "inav/src/main/rx/crsf.h", + "CRSF_ADDRESS_BROADCAST": "0", + "CRSF_ADDRESS_USB": "16", + "CRSF_ADDRESS_TBS_CORE_PNP_PRO": "128", + "CRSF_ADDRESS_RESERVED1": "138", + "CRSF_ADDRESS_CURRENT_SENSOR": "192", + "CRSF_ADDRESS_GPS": "194", + "CRSF_ADDRESS_TBS_BLACKBOX": "196", + "CRSF_ADDRESS_FLIGHT_CONTROLLER": "200", + "CRSF_ADDRESS_RESERVED2": "202", + "CRSF_ADDRESS_RACE_TAG": "204", + "CRSF_ADDRESS_RADIO_TRANSMITTER": "234", + "CRSF_ADDRESS_CRSF_RECEIVER": "236", + "CRSF_ADDRESS_CRSF_TRANSMITTER": "238" + }, + "crsfFrameType_e": { + "_source": "inav/src/main/rx/crsf.h", + "CRSF_FRAMETYPE_GPS": "2", + "CRSF_FRAMETYPE_VARIO_SENSOR": "7", + "CRSF_FRAMETYPE_BATTERY_SENSOR": "8", + "CRSF_FRAMETYPE_BAROMETER_ALTITUDE": "9", + "CRSF_FRAMETYPE_LINK_STATISTICS": "20", + "CRSF_FRAMETYPE_RC_CHANNELS_PACKED": "22", + "CRSF_FRAMETYPE_ATTITUDE": "30", + "CRSF_FRAMETYPE_FLIGHT_MODE": "33", + "CRSF_FRAMETYPE_DEVICE_PING": "40", + "CRSF_FRAMETYPE_DEVICE_INFO": "41", + "CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY": "43", + "CRSF_FRAMETYPE_PARAMETER_READ": "44", + "CRSF_FRAMETYPE_PARAMETER_WRITE": "45", + "CRSF_FRAMETYPE_COMMAND": "50", + "CRSF_FRAMETYPE_MSP_REQ": "122", + "CRSF_FRAMETYPE_MSP_RESP": "123", + "CRSF_FRAMETYPE_MSP_WRITE": "124", + "CRSF_FRAMETYPE_DISPLAYPORT_CMD": "125" + }, + "crsfFrameTypeIndex_e": { + "_source": "inav/src/main/telemetry/crsf.c", + "CRSF_FRAME_START_INDEX": "0", + "CRSF_FRAME_ATTITUDE_INDEX": "CRSF_FRAME_START_INDEX", + "CRSF_FRAME_BATTERY_SENSOR_INDEX": "", + "CRSF_FRAME_FLIGHT_MODE_INDEX": "", + "CRSF_FRAME_GPS_INDEX": "", + "CRSF_FRAME_VARIO_SENSOR_INDEX": "", + "CRSF_FRAME_BAROMETER_ALTITUDE_INDEX": "", + "CRSF_SCHEDULE_COUNT_MAX": "" + }, + "crsrRfMode_e": { + "_source": "inav/src/main/telemetry/crsf.c", + "CRSF_RF_MODE_4_HZ": "0", + "CRSF_RF_MODE_50_HZ": "1", + "CRSF_RF_MODE_150_HZ": "2" + }, + "crsrRfPower_e": { + "_source": "inav/src/main/telemetry/crsf.c", + "CRSF_RF_POWER_0_mW": "0", + "CRSF_RF_POWER_10_mW": "1", + "CRSF_RF_POWER_25_mW": "2", + "CRSF_RF_POWER_100_mW": "3", + "CRSF_RF_POWER_500_mW": "4", + "CRSF_RF_POWER_1000_mW": "5", + "CRSF_RF_POWER_2000_mW": "6", + "CRSF_RF_POWER_250_mW": "7" + }, + "currentSensor_e": { + "_source": "inav/src/main/sensors/battery_config_structs.h", + "CURRENT_SENSOR_NONE": "0", + "CURRENT_SENSOR_ADC": "1", + "CURRENT_SENSOR_VIRTUAL": "2", + "CURRENT_SENSOR_FAKE": "3", + "CURRENT_SENSOR_ESC": "4", + "CURRENT_SENSOR_SMARTPORT": "5", + "CURRENT_SENSOR_MAX": "CURRENT_SENSOR_SMARTPORT" + }, + "devHardwareType_e": { + "_source": "inav/src/main/drivers/bus.h", + "DEVHW_NONE": "0", + "DEVHW_MPU6000": "1", + "DEVHW_MPU6500": "2", + "DEVHW_BMI160": "3", + "DEVHW_BMI088_GYRO": "4", + "DEVHW_BMI088_ACC": "5", + "DEVHW_ICM20689": "6", + "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" + }, + "deviceFlags_e": { + "_source": "inav/src/main/drivers/bus.h", + "DEVFLAGS_NONE": "0", + "DEVFLAGS_USE_RAW_REGISTERS": "(1 << 0)", + "DEVFLAGS_USE_MANUAL_DEVICE_SELECT": "(1 << 1)", + "DEVFLAGS_SPI_MODE_0": "(1 << 2)" + }, + "disarmReason_t": { + "_source": "inav/src/main/fc/fc_core.h", + "DISARM_NONE": "0", + "DISARM_TIMEOUT": "1", + "DISARM_STICKS": "2", + "DISARM_SWITCH_3D": "3", + "DISARM_SWITCH": "4", + "DISARM_FAILSAFE": "6", + "DISARM_NAVIGATION": "7", + "DISARM_LANDING": "8", + "DISARM_REASON_COUNT": "9" + }, + "displayCanvasBitmapOption_t": { + "_source": "inav/src/main/drivers/display_canvas.h", + "DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS": "1 << 0", + "DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND": "1 << 1", + "DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT": "1 << 2" + }, + "displayCanvasColor_e": { + "_source": "inav/src/main/drivers/display_canvas.h", + "DISPLAY_CANVAS_COLOR_BLACK": "0", + "DISPLAY_CANVAS_COLOR_TRANSPARENT": "1", + "DISPLAY_CANVAS_COLOR_WHITE": "2", + "DISPLAY_CANVAS_COLOR_GRAY": "3" + }, + "displayCanvasOutlineType_e": { + "_source": "inav/src/main/drivers/display_canvas.h", + "DISPLAY_CANVAS_OUTLINE_TYPE_NONE": "0", + "DISPLAY_CANVAS_OUTLINE_TYPE_TOP": "1 << 0", + "DISPLAY_CANVAS_OUTLINE_TYPE_RIGHT": "1 << 1", + "DISPLAY_CANVAS_OUTLINE_TYPE_BOTTOM": "1 << 2", + "DISPLAY_CANVAS_OUTLINE_TYPE_LEFT": "1 << 3" + }, + "displayportMspCommand_e": { + "_source": "inav/src/main/io/displayport_msp.h", + "MSP_DP_HEARTBEAT": "0", + "MSP_DP_RELEASE": "1", + "MSP_DP_CLEAR_SCREEN": "2", + "MSP_DP_WRITE_STRING": "3", + "MSP_DP_DRAW_SCREEN": "4", + "MSP_DP_OPTIONS": "5", + "MSP_DP_SYS": "6", + "MSP_DP_COUNT": "7" + }, + "displayTransactionOption_e": { + "_source": "inav/src/main/drivers/display.h", + "DISPLAY_TRANSACTION_OPT_NONE": "0", + "DISPLAY_TRANSACTION_OPT_PROFILED": "1 << 0", + "DISPLAY_TRANSACTION_OPT_RESET_DRAWING": "1 << 1" + }, + "displayWidgetType_e": { + "_source": "inav/src/main/drivers/display_widgets.h", + "DISPLAY_WIDGET_TYPE_AHI": "0", + "DISPLAY_WIDGET_TYPE_SIDEBAR": "1" + }, + "DjiCraftNameElements_t": { + "_source": "inav/src/main/io/osd_dji_hd.c", + "DJI_OSD_CN_MESSAGES": "0", + "DJI_OSD_CN_THROTTLE": "1", + "DJI_OSD_CN_THROTTLE_AUTO_THR": "2", + "DJI_OSD_CN_AIR_SPEED": "3", + "DJI_OSD_CN_EFFICIENCY": "4", + "DJI_OSD_CN_DISTANCE": "5", + "DJI_OSD_CN_ADJUSTEMNTS": "6", + "DJI_OSD_CN_MAX_ELEMENTS": "7" + }, + "dshotCommands_e": { + "_source": "inav/src/main/drivers/pwm_output.h", + "DSHOT_CMD_SPIN_DIRECTION_NORMAL": "20", + "DSHOT_CMD_SPIN_DIRECTION_REVERSED": "21" + }, + "dumpFlags_e": { + "_source": "inav/src/main/fc/cli.c", + "DUMP_MASTER": "(1 << 0)", + "DUMP_CONTROL_PROFILE": "(1 << 1)", + "DUMP_BATTERY_PROFILE": "(1 << 2)", + "DUMP_MIXER_PROFILE": "(1 << 3)", + "DUMP_ALL": "(1 << 4)", + "DO_DIFF": "(1 << 5)", + "SHOW_DEFAULTS": "(1 << 6)", + "HIDE_UNUSED": "(1 << 7)" + }, + "dynamicGyroNotchMode_e": { + "_source": "inav/src/main/sensors/gyro.h", + "DYNAMIC_NOTCH_MODE_2D": "0", + "DYNAMIC_NOTCH_MODE_3D": "1" + }, + "emergLandState_e": { + "_source": "inav/src/main/flight/failsafe.h", + "EMERG_LAND_IDLE": "0", + "EMERG_LAND_IN_PROGRESS": "1", + "EMERG_LAND_HAS_LANDED": "2" + }, + "escSensorFrameStatus_t": { + "_source": "inav/src/main/sensors/esc_sensor.c", + "ESC_SENSOR_FRAME_PENDING": "0", + "ESC_SENSOR_FRAME_COMPLETE": "1", + "ESC_SENSOR_FRAME_FAILED": "2" + }, + "escSensorState_t": { + "_source": "inav/src/main/sensors/esc_sensor.c", + "ESC_SENSOR_WAIT_STARTUP": "0", + "ESC_SENSOR_READY": "1", + "ESC_SENSOR_WAITING": "2" + }, + "failsafeChannelBehavior_e": { + "_source": "inav/src/main/flight/failsafe.c", + "FAILSAFE_CHANNEL_HOLD": "0", + "FAILSAFE_CHANNEL_NEUTRAL": "1" + }, + "failsafePhase_e": { + "_source": "inav/src/main/flight/failsafe.h", + "FAILSAFE_IDLE": "0", + "FAILSAFE_RX_LOSS_DETECTED": "1", + "FAILSAFE_RX_LOSS_IDLE": "2", + "FAILSAFE_RETURN_TO_HOME": "3", + "FAILSAFE_LANDING": "4", + "FAILSAFE_LANDED": "5", + "FAILSAFE_RX_LOSS_MONITORING": "6", + "FAILSAFE_RX_LOSS_RECOVERED": "7" + }, + "failsafeProcedure_e": { + "_source": "inav/src/main/flight/failsafe.h", + "FAILSAFE_PROCEDURE_AUTO_LANDING": "0", + "FAILSAFE_PROCEDURE_DROP_IT": "1", + "FAILSAFE_PROCEDURE_RTH": "2", + "FAILSAFE_PROCEDURE_NONE": "3" + }, + "failsafeRxLinkState_e": { + "_source": "inav/src/main/flight/failsafe.h", + "FAILSAFE_RXLINK_DOWN": "0", + "FAILSAFE_RXLINK_UP": "1" + }, + "failureMode_e": { + "_source": "inav/src/main/drivers/system.h", + "FAILURE_DEVELOPER": "0", + "FAILURE_MISSING_ACC": "1", + "FAILURE_ACC_INIT": "2", + "FAILURE_ACC_INCOMPATIBLE": "3", + "FAILURE_INVALID_EEPROM_CONTENTS": "4", + "FAILURE_FLASH_WRITE_FAILED": "5", + "FAILURE_GYRO_INIT_FAILED": "6", + "FAILURE_FLASH_READ_FAILED": "7" + }, + "fatFilesystemType_e": { + "_source": "inav/src/main/io/asyncfatfs/fat_standard.h", + "FAT_FILESYSTEM_TYPE_INVALID": "0", + "FAT_FILESYSTEM_TYPE_FAT12": "1", + "FAT_FILESYSTEM_TYPE_FAT16": "2", + "FAT_FILESYSTEM_TYPE_FAT32": "3" + }, + "features_e": { + "_source": "inav/src/main/fc/config.h", + "FEATURE_THR_VBAT_COMP": "1 << 0", + "FEATURE_VBAT": "1 << 1", + "FEATURE_TX_PROF_SEL": "1 << 2", + "FEATURE_BAT_PROFILE_AUTOSWITCH": "1 << 3", + "FEATURE_GEOZONE": "1 << 4", + "FEATURE_UNUSED_1": "1 << 5", + "FEATURE_SOFTSERIAL": "1 << 6", + "FEATURE_GPS": "1 << 7", + "FEATURE_UNUSED_3": "1 << 8", + "FEATURE_UNUSED_4": "1 << 9", + "FEATURE_TELEMETRY": "1 << 10", + "FEATURE_CURRENT_METER": "1 << 11", + "FEATURE_REVERSIBLE_MOTORS": "1 << 12", + "FEATURE_UNUSED_5": "1 << 13", + "FEATURE_UNUSED_6": "1 << 14", + "FEATURE_RSSI_ADC": "1 << 15", + "FEATURE_LED_STRIP": "1 << 16", + "FEATURE_DASHBOARD": "1 << 17", + "FEATURE_UNUSED_7": "1 << 18", + "FEATURE_BLACKBOX": "1 << 19", + "FEATURE_UNUSED_10": "1 << 20", + "FEATURE_TRANSPONDER": "1 << 21", + "FEATURE_AIRMODE": "1 << 22", + "FEATURE_SUPEREXPO_RATES": "1 << 23", + "FEATURE_VTX": "1 << 24", + "FEATURE_UNUSED_8": "1 << 25", + "FEATURE_UNUSED_9": "1 << 26", + "FEATURE_UNUSED_11": "1 << 27", + "FEATURE_PWM_OUTPUT_ENABLE": "1 << 28", + "FEATURE_OSD": "1 << 29", + "FEATURE_FW_LAUNCH": "1 << 30", + "FEATURE_FW_AUTOTRIM": "1U << 31" + }, + "filterType_e": { + "_source": "inav/src/main/common/filter.h", + "FILTER_PT1": "0", + "FILTER_BIQUAD": "1", + "FILTER_PT2": "2", + "FILTER_PT3": "3", + "FILTER_LULU": "4" + }, + "fixedWingLaunchEvent_t": { + "_source": "inav/src/main/navigation/navigation_fw_launch.c", + "FW_LAUNCH_EVENT_NONE": "0", + "FW_LAUNCH_EVENT_SUCCESS": "1", + "FW_LAUNCH_EVENT_GOTO_DETECTION": "2", + "FW_LAUNCH_EVENT_ABORT": "3", + "FW_LAUNCH_EVENT_THROTTLE_LOW": "4", + "FW_LAUNCH_EVENT_COUNT": "5" + }, + "fixedWingLaunchMessage_t": { + "_source": "inav/src/main/navigation/navigation_fw_launch.c", + "FW_LAUNCH_MESSAGE_TYPE_NONE": "0", + "FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE": "1", + "FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE": "2", + "FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION": "3", + "FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS": "4", + "FW_LAUNCH_MESSAGE_TYPE_FINISHING": "5" + }, + "fixedWingLaunchState_t": { + "_source": "inav/src/main/navigation/navigation_fw_launch.c", + "FW_LAUNCH_STATE_WAIT_THROTTLE": "0", + "FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT": "1", + "FW_LAUNCH_STATE_IDLE_MOTOR_DELAY": "2", + "FW_LAUNCH_STATE_MOTOR_IDLE": "3", + "FW_LAUNCH_STATE_WAIT_DETECTION": "4", + "FW_LAUNCH_STATE_DETECTED": "5", + "FW_LAUNCH_STATE_MOTOR_DELAY": "6", + "FW_LAUNCH_STATE_MOTOR_SPINUP": "7", + "FW_LAUNCH_STATE_IN_PROGRESS": "8", + "FW_LAUNCH_STATE_FINISH": "9", + "FW_LAUNCH_STATE_ABORTED": "10", + "FW_LAUNCH_STATE_FLYING": "11", + "FW_LAUNCH_STATE_COUNT": "12" + }, + "flashPartitionType_e": { + "_source": "inav/src/main/drivers/flash.h", + "FLASH_PARTITION_TYPE_UNKNOWN": "0", + "FLASH_PARTITION_TYPE_PARTITION_TABLE": "1", + "FLASH_PARTITION_TYPE_FLASHFS": "2", + "FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT": "3", + "FLASH_PARTITION_TYPE_FIRMWARE": "4", + "FLASH_PARTITION_TYPE_CONFIG": "5", + "FLASH_PARTITION_TYPE_FULL_BACKUP": "6", + "FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META": "7", + "FLASH_PARTITION_TYPE_UPDATE_FIRMWARE": "8", + "FLASH_MAX_PARTITIONS": "9" + }, + "flashType_e": { + "_source": "inav/src/main/drivers/flash.h", + "FLASH_TYPE_NOR": "0", + "FLASH_TYPE_NAND": "1" + }, + "flight_dynamics_index_t": { + "_source": "inav/src/main/common/axis.h", + "FD_ROLL": "0", + "FD_PITCH": "1", + "FD_YAW": "2" + }, + "FlightLogEvent": { + "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", + "FLIGHT_LOG_EVENT_SYNC_BEEP": "0", + "FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT": "13", + "FLIGHT_LOG_EVENT_LOGGING_RESUME": "14", + "FLIGHT_LOG_EVENT_FLIGHTMODE": "30", + "FLIGHT_LOG_EVENT_IMU_FAILURE": "40", + "FLIGHT_LOG_EVENT_LOG_END": "255" + }, + "FlightLogFieldCondition": { + "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", + "FLIGHT_LOG_FIELD_CONDITION_ALWAYS": "0", + "FLIGHT_LOG_FIELD_CONDITION_MOTORS": "1", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1": "2", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2": "3", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3": "4", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4": "5", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5": "6", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6": "7", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7": "8", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8": "9", + "FLIGHT_LOG_FIELD_CONDITION_SERVOS": "10", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1": "11", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2": "12", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3": "13", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4": "14", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5": "15", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6": "16", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7": "17", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8": "18", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9": "19", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10": "20", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11": "21", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12": "22", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13": "23", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14": "24", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15": "25", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16": "26", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17": "27", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18": "28", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19": "29", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20": "30", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21": "31", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22": "32", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23": "33", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24": "34", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25": "35", + "FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26": "36", + "FLIGHT_LOG_FIELD_CONDITION_MAG": "37", + "FLIGHT_LOG_FIELD_CONDITION_BARO": "38", + "FLIGHT_LOG_FIELD_CONDITION_PITOT": "39", + "FLIGHT_LOG_FIELD_CONDITION_VBAT": "40", + "FLIGHT_LOG_FIELD_CONDITION_AMPERAGE": "41", + "FLIGHT_LOG_FIELD_CONDITION_SURFACE": "42", + "FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV": "43", + "FLIGHT_LOG_FIELD_CONDITION_MC_NAV": "44", + "FLIGHT_LOG_FIELD_CONDITION_RSSI": "45", + "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0": "46", + "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1": "47", + "FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2": "48", + "FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME": "49", + "FLIGHT_LOG_FIELD_CONDITION_DEBUG": "50", + "FLIGHT_LOG_FIELD_CONDITION_NAV_ACC": "51", + "FLIGHT_LOG_FIELD_CONDITION_NAV_POS": "52", + "FLIGHT_LOG_FIELD_CONDITION_NAV_PID": "53", + "FLIGHT_LOG_FIELD_CONDITION_ACC": "54", + "FLIGHT_LOG_FIELD_CONDITION_ATTITUDE": "55", + "FLIGHT_LOG_FIELD_CONDITION_RC_DATA": "56", + "FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND": "57", + "FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW": "58", + "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_ROLL": "59", + "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_PITCH": "60", + "FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_YAW": "61", + "FLIGHT_LOG_FIELD_CONDITION_NEVER": "62", + "FLIGHT_LOG_FIELD_CONDITION_FIRST": "FLIGHT_LOG_FIELD_CONDITION_ALWAYS", + "FLIGHT_LOG_FIELD_CONDITION_LAST": "FLIGHT_LOG_FIELD_CONDITION_NEVER" + }, + "FlightLogFieldEncoding": { + "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", + "FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB": "0", + "FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB": "1", + "FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT": "3", + "FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB": "6", + "FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32": "7", + "FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16": "8", + "FLIGHT_LOG_FIELD_ENCODING_NULL": "9" + }, + "FlightLogFieldPredictor": { + "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", + "FLIGHT_LOG_FIELD_PREDICTOR_0": "0", + "FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS": "1", + "FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE": "2", + "FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2": "3", + "FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE": "4", + "FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0": "5", + "FLIGHT_LOG_FIELD_PREDICTOR_INC": "6", + "FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD": "7", + "FLIGHT_LOG_FIELD_PREDICTOR_1500": "8", + "FLIGHT_LOG_FIELD_PREDICTOR_VBATREF": "9", + "FLIGHT_LOG_FIELD_PREDICTOR_LAST_MAIN_FRAME_TIME": "10" + }, + "FlightLogFieldSign": { + "_source": "inav/src/main/blackbox/blackbox_fielddefs.h", + "FLIGHT_LOG_FIELD_UNSIGNED": "0", + "FLIGHT_LOG_FIELD_SIGNED": "1" + }, + "flightModeFlags_e": { + "_source": "inav/src/main/fc/runtime_config.h", + "ANGLE_MODE": "(1 << 0)", + "HORIZON_MODE": "(1 << 1)", + "HEADING_MODE": "(1 << 2)", + "NAV_ALTHOLD_MODE": "(1 << 3)", + "NAV_RTH_MODE": "(1 << 4)", + "NAV_POSHOLD_MODE": "(1 << 5)", + "HEADFREE_MODE": "(1 << 6)", + "NAV_LAUNCH_MODE": "(1 << 7)", + "MANUAL_MODE": "(1 << 8)", + "FAILSAFE_MODE": "(1 << 9)", + "AUTO_TUNE": "(1 << 10)", + "NAV_WP_MODE": "(1 << 11)", + "NAV_COURSE_HOLD_MODE": "(1 << 12)", + "FLAPERON": "(1 << 13)", + "TURN_ASSISTANT": "(1 << 14)", + "TURTLE_MODE": "(1 << 15)", + "SOARING_MODE": "(1 << 16)", + "ANGLEHOLD_MODE": "(1 << 17)", + "NAV_FW_AUTOLAND": "(1 << 18)", + "NAV_SEND_TO": "(1 << 19)" + }, + "flightModeForTelemetry_e": { + "_source": "inav/src/main/fc/runtime_config.h", + "FLM_MANUAL": "0", + "FLM_ACRO": "1", + "FLM_ACRO_AIR": "2", + "FLM_ANGLE": "3", + "FLM_HORIZON": "4", + "FLM_ALTITUDE_HOLD": "5", + "FLM_POSITION_HOLD": "6", + "FLM_RTH": "7", + "FLM_MISSION": "8", + "FLM_COURSE_HOLD": "9", + "FLM_CRUISE": "10", + "FLM_LAUNCH": "11", + "FLM_FAILSAFE": "12", + "FLM_ANGLEHOLD": "13", + "FLM_COUNT": "14" + }, + "flyingPlatformType_e": { + "_source": "inav/src/main/flight/mixer.h", + "PLATFORM_MULTIROTOR": "0", + "PLATFORM_AIRPLANE": "1", + "PLATFORM_HELICOPTER": "2", + "PLATFORM_TRICOPTER": "3", + "PLATFORM_ROVER": "4", + "PLATFORM_BOAT": "5" + }, + "fport2_control_frame_type_e": { + "_source": "inav/src/main/rx/fport2.c", + "CFT_RC": "255", + "CFT_OTA_START": "240", + "CFT_OTA_DATA": "241", + "CFT_OTA_STOP": "242" + }, + "frame_state_e": { + "_source": "inav/src/main/rx/fport2.c", + "FS_CONTROL_FRAME_START": "0", + "FS_CONTROL_FRAME_TYPE": "1", + "FS_CONTROL_FRAME_DATA": "2", + "FS_DOWNLINK_FRAME_START": "3", + "FS_DOWNLINK_FRAME_DATA": "4" + }, + "frame_type_e": { + "_source": "inav/src/main/rx/fport2.c", + "FT_CONTROL": "0", + "FT_DOWNLINK": "1" + }, + "frskyOSDColor_e": { + "_source": "inav/src/main/io/frsky_osd.h", + "FRSKY_OSD_COLOR_BLACK": "0", + "FRSKY_OSD_COLOR_TRANSPARENT": "1", + "FRSKY_OSD_COLOR_WHITE": "2", + "FRSKY_OSD_COLOR_GRAY": "3" + }, + "frskyOSDLineOutlineType_e": { + "_source": "inav/src/main/io/frsky_osd.h", + "FRSKY_OSD_OUTLINE_TYPE_NONE": "0", + "FRSKY_OSD_OUTLINE_TYPE_TOP": "1 << 0", + "FRSKY_OSD_OUTLINE_TYPE_RIGHT": "1 << 1", + "FRSKY_OSD_OUTLINE_TYPE_BOTTOM": "1 << 2", + "FRSKY_OSD_OUTLINE_TYPE_LEFT": "1 << 3" + }, + "frskyOSDRecvState_e": { + "_source": "inav/src/main/io/frsky_osd.c", + "RECV_STATE_NONE": "0", + "RECV_STATE_SYNC": "1", + "RECV_STATE_LENGTH": "2", + "RECV_STATE_DATA": "3", + "RECV_STATE_CHECKSUM": "4", + "RECV_STATE_DONE": "5" + }, + "frskyOSDTransactionOptions_e": { + "_source": "inav/src/main/io/frsky_osd.h", + "FRSKY_OSD_TRANSACTION_OPT_PROFILED": "1 << 0", + "FRSKY_OSD_TRANSACTION_OPT_RESET_DRAWING": "1 << 1" + }, + "fw_autotune_rate_adjustment_e": { + "_source": "inav/src/main/flight/pid.h", + "FIXED": "0", + "LIMIT": "1", + "AUTO": "2" + }, + "fwAutolandApproachDirection_e": { + "_source": "inav/src/main/navigation/navigation.h", + "FW_AUTOLAND_APPROACH_DIRECTION_LEFT": "0", + "FW_AUTOLAND_APPROACH_DIRECTION_RIGHT": "1" + }, + "fwAutolandState_t": { + "_source": "inav/src/main/navigation/navigation.h", + "FW_AUTOLAND_STATE_IDLE": "0", + "FW_AUTOLAND_STATE_LOITER": "1", + "FW_AUTOLAND_STATE_DOWNWIND": "2", + "FW_AUTOLAND_STATE_BASE_LEG": "3", + "FW_AUTOLAND_STATE_FINAL_APPROACH": "4", + "FW_AUTOLAND_STATE_GLIDE": "5", + "FW_AUTOLAND_STATE_FLARE": "6" + }, + "fwAutolandWaypoint_t": { + "_source": "inav/src/main/navigation/navigation_private.h", + "FW_AUTOLAND_WP_TURN": "0", + "FW_AUTOLAND_WP_FINAL_APPROACH": "1", + "FW_AUTOLAND_WP_LAND": "2", + "FW_AUTOLAND_WP_COUNT": "3" + }, + "geoAltitudeConversionMode_e": { + "_source": "inav/src/main/navigation/navigation.h", + "GEO_ALT_ABSOLUTE": "0", + "GEO_ALT_RELATIVE": "1" + }, + "geoAltitudeDatumFlag_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_WP_TAKEOFF_DATUM": "0", + "NAV_WP_MSL_DATUM": "1" + }, + "geoOriginResetMode_e": { + "_source": "inav/src/main/navigation/navigation.h", + "GEO_ORIGIN_SET": "0", + "GEO_ORIGIN_RESET_ALTITUDE": "1" + }, + "geozoneActionState_e": { + "_source": "inav/src/main/navigation/navigation_geozone.c", + "GEOZONE_ACTION_STATE_NONE": "0", + "GEOZONE_ACTION_STATE_AVOIDING": "1", + "GEOZONE_ACTION_STATE_AVOIDING_UPWARD": "2", + "GEOZONE_ACTION_STATE_AVOIDING_ALTITUDE": "3", + "GEOZONE_ACTION_STATE_RETURN_TO_FZ": "4", + "GEOZONE_ACTION_STATE_FLYOUT_NFZ": "5", + "GEOZONE_ACTION_STATE_POSHOLD": "6", + "GEOZONE_ACTION_STATE_RTH": "7" + }, + "geozoneMessageState_e": { + "_source": "inav/src/main/navigation/navigation.h", + "GEOZONE_MESSAGE_STATE_NONE": "0", + "GEOZONE_MESSAGE_STATE_NFZ": "1", + "GEOZONE_MESSAGE_STATE_LEAVING_FZ": "2", + "GEOZONE_MESSAGE_STATE_OUTSIDE_FZ": "3", + "GEOZONE_MESSAGE_STATE_ENTERING_NFZ": "4", + "GEOZONE_MESSAGE_STATE_AVOIDING_FB": "5", + "GEOZONE_MESSAGE_STATE_RETURN_TO_ZONE": "6", + "GEOZONE_MESSAGE_STATE_FLYOUT_NFZ": "7", + "GEOZONE_MESSAGE_STATE_AVOIDING_ALTITUDE_BREACH": "8", + "GEOZONE_MESSAGE_STATE_POS_HOLD": "9" + }, + "ghstAddr_e": { + "_source": "inav/src/main/rx/ghst_protocol.h", + "GHST_ADDR_RADIO": "128", + "GHST_ADDR_TX_MODULE_SYM": "129", + "GHST_ADDR_TX_MODULE_ASYM": "136", + "GHST_ADDR_FC": "130", + "GHST_ADDR_GOGGLES": "131", + "GHST_ADDR_QUANTUM_TEE1": "132", + "GHST_ADDR_QUANTUM_TEE2": "133", + "GHST_ADDR_QUANTUM_GW1": "134", + "GHST_ADDR_5G_CLK": "135", + "GHST_ADDR_RX": "137" + }, + "ghstDl_e": { + "_source": "inav/src/main/rx/ghst_protocol.h", + "GHST_DL_OPENTX_SYNC": "32", + "GHST_DL_LINK_STAT": "33", + "GHST_DL_VTX_STAT": "34", + "GHST_DL_PACK_STAT": "35", + "GHST_DL_GPS_PRIMARY": "37", + "GHST_DL_GPS_SECONDARY": "38" + }, + "ghstFrameTypeIndex_e": { + "_source": "inav/src/main/telemetry/ghst.c", + "GHST_FRAME_START_INDEX": "0", + "GHST_FRAME_PACK_INDEX": "GHST_FRAME_START_INDEX", + "GHST_FRAME_GPS_PRIMARY_INDEX": "", + "GHST_FRAME_GPS_SECONDARY_INDEX": "", + "GHST_SCHEDULE_COUNT_MAX": "" + }, + "ghstUl_e": { + "_source": "inav/src/main/rx/ghst_protocol.h", + "GHST_UL_RC_CHANS_HS4_FIRST": "16", + "GHST_UL_RC_CHANS_HS4_5TO8": "16", + "GHST_UL_RC_CHANS_HS4_9TO12": "17", + "GHST_UL_RC_CHANS_HS4_13TO16": "18", + "GHST_UL_RC_CHANS_HS4_RSSI": "19", + "GHST_UL_RC_CHANS_HS4_LAST": "31" + }, + "gimbal_htk_mode_e": { + "_source": "inav/src/main/drivers/gimbal_common.h", + "GIMBAL_MODE_FOLLOW": "0", + "GIMBAL_MODE_TILT_LOCK": "(1<<0)", + "GIMBAL_MODE_ROLL_LOCK": "(1<<1)", + "GIMBAL_MODE_PAN_LOCK": "(1<<2)" + }, + "gimbalDevType_e": { + "_source": "inav/src/main/drivers/gimbal_common.h", + "GIMBAL_DEV_UNSUPPORTED": "0", + "GIMBAL_DEV_SERIAL": "1", + "GIMBAL_DEV_UNKNOWN": "255" + }, + "gimbalHeadtrackerState_e": { + "_source": "inav/src/main/io/gimbal_serial.h", + "WAITING_HDR1": "0", + "WAITING_HDR2": "1", + "WAITING_PAYLOAD": "2", + "WAITING_CRCH": "3", + "WAITING_CRCL": "4" + }, + "gpsAutoBaud_e": { + "_source": "inav/src/main/io/gps.h", + "GPS_AUTOBAUD_OFF": "0", + "GPS_AUTOBAUD_ON": "1" + }, + "gpsAutoConfig_e": { + "_source": "inav/src/main/io/gps.h", + "GPS_AUTOCONFIG_OFF": "0", + "GPS_AUTOCONFIG_ON": "1" + }, + "gpsBaudRate_e": { + "_source": "inav/src/main/io/gps.h", + "GPS_BAUDRATE_115200": "0", + "GPS_BAUDRATE_57600": "1", + "GPS_BAUDRATE_38400": "2", + "GPS_BAUDRATE_19200": "3", + "GPS_BAUDRATE_9600": "4", + "GPS_BAUDRATE_230400": "5", + "GPS_BAUDRATE_460800": "6", + "GPS_BAUDRATE_921600": "7", + "GPS_BAUDRATE_COUNT": "8" + }, + "gpsDynModel_e": { + "_source": "inav/src/main/io/gps.h", + "GPS_DYNMODEL_PEDESTRIAN": "0", + "GPS_DYNMODEL_AUTOMOTIVE": "1", + "GPS_DYNMODEL_AIR_1G": "2", + "GPS_DYNMODEL_AIR_2G": "3", + "GPS_DYNMODEL_AIR_4G": "4", + "GPS_DYNMODEL_SEA": "5", + "GPS_DYNMODEL_MOWER": "6" + }, + "gpsFixChar_e": { + "_source": "inav/src/main/telemetry/hott.c", + "GPS_FIX_CHAR_NONE": "'-'", + "GPS_FIX_CHAR_2D": "'2'", + "GPS_FIX_CHAR_3D": "'3'", + "GPS_FIX_CHAR_DGPS": "'D'" + }, + "gpsFixType_e": { + "_source": "inav/src/main/io/gps.h", + "GPS_NO_FIX": "0", + "GPS_FIX_2D": "1", + "GPS_FIX_3D": "2" + }, + "gpsProvider_e": { + "_source": "inav/src/main/io/gps.h", + "GPS_UBLOX": "0", + "GPS_MSP": "1", + "GPS_FAKE": "2", + "GPS_PROVIDER_COUNT": "3" + }, + "gpsState_e": { + "_source": "inav/src/main/io/gps_private.h", + "GPS_UNKNOWN": "0", + "GPS_INITIALIZING": "1", + "GPS_RUNNING": "2", + "GPS_LOST_COMMUNICATION": "3" + }, + "gyroFilterMode_e": { + "_source": "inav/src/main/sensors/gyro.h", + "GYRO_FILTER_MODE_OFF": "0", + "GYRO_FILTER_MODE_STATIC": "1", + "GYRO_FILTER_MODE_DYNAMIC": "2", + "GYRO_FILTER_MODE_ADAPTIVE": "3" + }, + "gyroHardwareLpf_e": { + "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", + "GYRO_HARDWARE_LPF_NORMAL": "0", + "GYRO_HARDWARE_LPF_OPTION_1": "1", + "GYRO_HARDWARE_LPF_OPTION_2": "2", + "GYRO_HARDWARE_LPF_EXPERIMENTAL": "3", + "GYRO_HARDWARE_LPF_COUNT": "4" + }, + "gyroSensor_e": { + "_source": "inav/src/main/sensors/gyro.h", + "GYRO_NONE": "0", + "GYRO_AUTODETECT": "1", + "GYRO_MPU6000": "2", + "GYRO_MPU6500": "3", + "GYRO_MPU9250": "4", + "GYRO_BMI160": "5", + "GYRO_ICM20689": "6", + "GYRO_BMI088": "7", + "GYRO_ICM42605": "8", + "GYRO_BMI270": "9", + "GYRO_LSM6DXX": "10", + "GYRO_FAKE": "11" + }, + "HardwareMotorTypes_e": { + "_source": "inav/src/main/drivers/pwm_esc_detect.h", + "MOTOR_UNKNOWN": "0", + "MOTOR_BRUSHED": "1", + "MOTOR_BRUSHLESS": "2" + }, + "hardwareSensorStatus_e": { + "_source": "inav/src/main/sensors/diagnostics.h", + "HW_SENSOR_NONE": "0", + "HW_SENSOR_OK": "1", + "HW_SENSOR_UNAVAILABLE": "2", + "HW_SENSOR_UNHEALTHY": "3" + }, + "headTrackerDevType_e": { + "_source": "inav/src/main/drivers/headtracker_common.h", + "HEADTRACKER_NONE": "0", + "HEADTRACKER_SERIAL": "1", + "HEADTRACKER_MSP": "2", + "HEADTRACKER_UNKNOWN": "255" + }, + "hottEamAlarm1Flag_e": { + "_source": "inav/src/main/telemetry/hott.h", + "HOTT_EAM_ALARM1_FLAG_NONE": "0", + "HOTT_EAM_ALARM1_FLAG_MAH": "(1 << 0)", + "HOTT_EAM_ALARM1_FLAG_BATTERY_1": "(1 << 1)", + "HOTT_EAM_ALARM1_FLAG_BATTERY_2": "(1 << 2)", + "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1": "(1 << 3)", + "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2": "(1 << 4)", + "HOTT_EAM_ALARM1_FLAG_ALTITUDE": "(1 << 5)", + "HOTT_EAM_ALARM1_FLAG_CURRENT": "(1 << 6)", + "HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE": "(1 << 7)" + }, + "hottEamAlarm2Flag_e": { + "_source": "inav/src/main/telemetry/hott.h", + "HOTT_EAM_ALARM2_FLAG_NONE": "0", + "HOTT_EAM_ALARM2_FLAG_MS": "(1 << 0)", + "HOTT_EAM_ALARM2_FLAG_M3S": "(1 << 1)", + "HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE": "(1 << 2)", + "HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE": "(1 << 3)", + "HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE": "(1 << 4)", + "HOTT_EAM_ALARM2_FLAG_UNKNOWN_1": "(1 << 5)", + "HOTT_EAM_ALARM2_FLAG_UNKNOWN_2": "(1 << 6)", + "HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE": "(1 << 7)" + }, + "hottState_e": { + "_source": "inav/src/main/telemetry/hott.c", + "HOTT_WAITING_FOR_REQUEST": "0", + "HOTT_RECEIVING_REQUEST": "1", + "HOTT_WAITING_FOR_TX_WINDOW": "2", + "HOTT_TRANSMITTING": "3", + "HOTT_ENDING_TRANSMISSION": "4" + }, + "hsvColorComponent_e": { + "_source": "inav/src/main/common/color.h", + "HSV_HUE": "0", + "HSV_SATURATION": "1", + "HSV_VALUE": "2" + }, + "I2CDevice": { + "_source": "inav/src/main/drivers/bus_i2c.h", + "I2CINVALID": "-1", + "I2CDEV_EMULATED": "-1", + "I2CDEV_1": "0", + "I2CDEV_2": "1", + "I2CDEV_3": "2", + "I2CDEV_4": [ + "(3)", + "USE_I2C_DEVICE_4" + ], + "I2CDEV_COUNT": "4" + }, + "I2CSpeed": { + "_source": "inav/src/main/drivers/bus_i2c.h", + "I2C_SPEED_100KHZ": "2", + "I2C_SPEED_200KHZ": "3", + "I2C_SPEED_400KHZ": "0", + "I2C_SPEED_800KHZ": "1" + }, + "i2cState_t": { + "_source": "inav/src/main/drivers/bus_i2c_stm32f40x.c", + "I2C_STATE_STOPPED": "0", + "I2C_STATE_STOPPING": "1", + "I2C_STATE_STARTING": "2", + "I2C_STATE_STARTING_WAIT": "3", + "I2C_STATE_R_ADDR": "4", + "I2C_STATE_R_ADDR_WAIT": "5", + "I2C_STATE_R_REGISTER": "6", + "I2C_STATE_R_REGISTER_WAIT": "7", + "I2C_STATE_R_RESTARTING": "8", + "I2C_STATE_R_RESTARTING_WAIT": "9", + "I2C_STATE_R_RESTART_ADDR": "10", + "I2C_STATE_R_RESTART_ADDR_WAIT": "11", + "I2C_STATE_R_TRANSFER_EQ1": "12", + "I2C_STATE_R_TRANSFER_EQ2": "13", + "I2C_STATE_R_TRANSFER_GE2": "14", + "I2C_STATE_W_ADDR": "15", + "I2C_STATE_W_ADDR_WAIT": "16", + "I2C_STATE_W_REGISTER": "17", + "I2C_STATE_W_TRANSFER_WAIT": "18", + "I2C_STATE_W_TRANSFER": "19", + "I2C_STATE_NACK": "20", + "I2C_STATE_BUS_ERROR": "21" + }, + "i2cTransferDirection_t": { + "_source": "inav/src/main/drivers/bus_i2c_stm32f40x.c", + "I2C_TXN_READ": "0", + "I2C_TXN_WRITE": "1" + }, + "ibusCommand_e": { + "_source": "inav/src/main/telemetry/ibus_shared.c", + "IBUS_COMMAND_DISCOVER_SENSOR": "128", + "IBUS_COMMAND_SENSOR_TYPE": "144", + "IBUS_COMMAND_MEASUREMENT": "160" + }, + "ibusSensorType1_e": { + "_source": "inav/src/main/telemetry/ibus_shared.h", + "IBUS_MEAS_TYPE1_INTV": "0", + "IBUS_MEAS_TYPE1_TEM": "1", + "IBUS_MEAS_TYPE1_MOT": "2", + "IBUS_MEAS_TYPE1_EXTV": "3", + "IBUS_MEAS_TYPE1_CELL": "4", + "IBUS_MEAS_TYPE1_BAT_CURR": "5", + "IBUS_MEAS_TYPE1_FUEL": "6", + "IBUS_MEAS_TYPE1_RPM": "7", + "IBUS_MEAS_TYPE1_CMP_HEAD": "8", + "IBUS_MEAS_TYPE1_CLIMB_RATE": "9", + "IBUS_MEAS_TYPE1_COG": "10", + "IBUS_MEAS_TYPE1_GPS_STATUS": "11", + "IBUS_MEAS_TYPE1_ACC_X": "12", + "IBUS_MEAS_TYPE1_ACC_Y": "13", + "IBUS_MEAS_TYPE1_ACC_Z": "14", + "IBUS_MEAS_TYPE1_ROLL": "15", + "IBUS_MEAS_TYPE1_PITCH": "16", + "IBUS_MEAS_TYPE1_YAW": "17", + "IBUS_MEAS_TYPE1_VERTICAL_SPEED": "18", + "IBUS_MEAS_TYPE1_GROUND_SPEED": "19", + "IBUS_MEAS_TYPE1_GPS_DIST": "20", + "IBUS_MEAS_TYPE1_ARMED": "21", + "IBUS_MEAS_TYPE1_FLIGHT_MODE": "22", + "IBUS_MEAS_TYPE1_PRES": "65", + "IBUS_MEAS_TYPE1_SPE": "126", + "IBUS_MEAS_TYPE1_GPS_LAT": "128", + "IBUS_MEAS_TYPE1_GPS_LON": "129", + "IBUS_MEAS_TYPE1_GPS_ALT": "130", + "IBUS_MEAS_TYPE1_ALT": "131", + "IBUS_MEAS_TYPE1_S84": "132", + "IBUS_MEAS_TYPE1_S85": "133", + "IBUS_MEAS_TYPE1_S86": "134", + "IBUS_MEAS_TYPE1_S87": "135", + "IBUS_MEAS_TYPE1_S88": "136", + "IBUS_MEAS_TYPE1_S89": "137", + "IBUS_MEAS_TYPE1_S8a": "138" + }, + "ibusSensorType_e": { + "_source": "inav/src/main/telemetry/ibus_shared.h", + "IBUS_MEAS_TYPE_INTERNAL_VOLTAGE": "0", + "IBUS_MEAS_TYPE_TEMPERATURE": "1", + "IBUS_MEAS_TYPE_RPM": "2", + "IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE": "3", + "IBUS_MEAS_TYPE_HEADING": "4", + "IBUS_MEAS_TYPE_CURRENT": "5", + "IBUS_MEAS_TYPE_CLIMB": "6", + "IBUS_MEAS_TYPE_ACC_Z": "7", + "IBUS_MEAS_TYPE_ACC_Y": "8", + "IBUS_MEAS_TYPE_ACC_X": "9", + "IBUS_MEAS_TYPE_VSPEED": "10", + "IBUS_MEAS_TYPE_SPEED": "11", + "IBUS_MEAS_TYPE_DIST": "12", + "IBUS_MEAS_TYPE_ARMED": "13", + "IBUS_MEAS_TYPE_MODE": "14", + "IBUS_MEAS_TYPE_PRES": "65", + "IBUS_MEAS_TYPE_SPE": "126", + "IBUS_MEAS_TYPE_COG": "128", + "IBUS_MEAS_TYPE_GPS_STATUS": "129", + "IBUS_MEAS_TYPE_GPS_LON": "130", + "IBUS_MEAS_TYPE_GPS_LAT": "131", + "IBUS_MEAS_TYPE_ALT": "132", + "IBUS_MEAS_TYPE_S85": "133", + "IBUS_MEAS_TYPE_S86": "134", + "IBUS_MEAS_TYPE_S87": "135", + "IBUS_MEAS_TYPE_S88": "136", + "IBUS_MEAS_TYPE_S89": "137", + "IBUS_MEAS_TYPE_S8A": "138", + "IBUS_MEAS_TYPE_GALT": "249", + "IBUS_MEAS_TYPE_GPS": "253" + }, + "ibusSensorValue_e": { + "_source": "inav/src/main/telemetry/ibus_shared.h", + "IBUS_MEAS_VALUE_NONE": "0", + "IBUS_MEAS_VALUE_TEMPERATURE": "1", + "IBUS_MEAS_VALUE_MOT": "2", + "IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE": "3", + "IBUS_MEAS_VALUE_CELL": "4", + "IBUS_MEAS_VALUE_CURRENT": "5", + "IBUS_MEAS_VALUE_FUEL": "6", + "IBUS_MEAS_VALUE_RPM": "7", + "IBUS_MEAS_VALUE_HEADING": "8", + "IBUS_MEAS_VALUE_CLIMB": "9", + "IBUS_MEAS_VALUE_COG": "10", + "IBUS_MEAS_VALUE_GPS_STATUS": "11", + "IBUS_MEAS_VALUE_ACC_X": "12", + "IBUS_MEAS_VALUE_ACC_Y": "13", + "IBUS_MEAS_VALUE_ACC_Z": "14", + "IBUS_MEAS_VALUE_ROLL": "15", + "IBUS_MEAS_VALUE_PITCH": "16", + "IBUS_MEAS_VALUE_YAW": "17", + "IBUS_MEAS_VALUE_VSPEED": "18", + "IBUS_MEAS_VALUE_SPEED": "19", + "IBUS_MEAS_VALUE_DIST": "20", + "IBUS_MEAS_VALUE_ARMED": "21", + "IBUS_MEAS_VALUE_MODE": "22", + "IBUS_MEAS_VALUE_PRES": "65", + "IBUS_MEAS_VALUE_SPE": "126", + "IBUS_MEAS_VALUE_GPS_LAT": "128", + "IBUS_MEAS_VALUE_GPS_LON": "129", + "IBUS_MEAS_VALUE_GALT4": "130", + "IBUS_MEAS_VALUE_ALT4": "131", + "IBUS_MEAS_VALUE_GALT": "132", + "IBUS_MEAS_VALUE_ALT": "133", + "IBUS_MEAS_VALUE_STATUS": "135", + "IBUS_MEAS_VALUE_GPS_LAT1": "136", + "IBUS_MEAS_VALUE_GPS_LON1": "137", + "IBUS_MEAS_VALUE_GPS_LAT2": "144", + "IBUS_MEAS_VALUE_GPS_LON2": "145", + "IBUS_MEAS_VALUE_GPS": "253" + }, + "inputSource_e": { + "_source": "inav/src/main/flight/servos.h", + "INPUT_STABILIZED_ROLL": "0", + "INPUT_STABILIZED_PITCH": "1", + "INPUT_STABILIZED_YAW": "2", + "INPUT_STABILIZED_THROTTLE": "3", + "INPUT_RC_ROLL": "4", + "INPUT_RC_PITCH": "5", + "INPUT_RC_YAW": "6", + "INPUT_RC_THROTTLE": "7", + "INPUT_RC_CH5": "8", + "INPUT_RC_CH6": "9", + "INPUT_RC_CH7": "10", + "INPUT_RC_CH8": "11", + "INPUT_GIMBAL_PITCH": "12", + "INPUT_GIMBAL_ROLL": "13", + "INPUT_FEATURE_FLAPS": "14", + "INPUT_RC_CH9": "15", + "INPUT_RC_CH10": "16", + "INPUT_RC_CH11": "17", + "INPUT_RC_CH12": "18", + "INPUT_RC_CH13": "19", + "INPUT_RC_CH14": "20", + "INPUT_RC_CH15": "21", + "INPUT_RC_CH16": "22", + "INPUT_STABILIZED_ROLL_PLUS": "23", + "INPUT_STABILIZED_ROLL_MINUS": "24", + "INPUT_STABILIZED_PITCH_PLUS": "25", + "INPUT_STABILIZED_PITCH_MINUS": "26", + "INPUT_STABILIZED_YAW_PLUS": "27", + "INPUT_STABILIZED_YAW_MINUS": "28", + "INPUT_MAX": "29", + "INPUT_GVAR_0": "30", + "INPUT_GVAR_1": "31", + "INPUT_GVAR_2": "32", + "INPUT_GVAR_3": "33", + "INPUT_GVAR_4": "34", + "INPUT_GVAR_5": "35", + "INPUT_GVAR_6": "36", + "INPUT_GVAR_7": "37", + "INPUT_MIXER_TRANSITION": "38", + "INPUT_HEADTRACKER_PAN": "39", + "INPUT_HEADTRACKER_TILT": "40", + "INPUT_HEADTRACKER_ROLL": "41", + "INPUT_RC_CH17": "42", + "INPUT_RC_CH18": "43", + "INPUT_RC_CH19": "44", + "INPUT_RC_CH20": "45", + "INPUT_RC_CH21": "46", + "INPUT_RC_CH22": "47", + "INPUT_RC_CH23": "48", + "INPUT_RC_CH24": "49", + "INPUT_RC_CH25": "50", + "INPUT_RC_CH26": "51", + "INPUT_RC_CH27": "52", + "INPUT_RC_CH28": "53", + "INPUT_RC_CH29": "54", + "INPUT_RC_CH30": "55", + "INPUT_RC_CH31": "56", + "INPUT_RC_CH32": "57", + "INPUT_RC_CH33": "58", + "INPUT_RC_CH34": "59", + "INPUT_MIXER_SWITCH_HELPER": "60", + "INPUT_SOURCE_COUNT": "61" + }, + "itermRelax_e": { + "_source": "inav/src/main/flight/pid.h", + "ITERM_RELAX_OFF": "0", + "ITERM_RELAX_RP": "1", + "ITERM_RELAX_RPY": "2" + }, + "led_pin_pwm_mode_e": { + "_source": "inav/src/main/drivers/light_ws2811strip.h", + "LED_PIN_PWM_MODE_SHARED_LOW": "0", + "LED_PIN_PWM_MODE_SHARED_HIGH": "1", + "LED_PIN_PWM_MODE_LOW": "2", + "LED_PIN_PWM_MODE_HIGH": "3" + }, + "ledBaseFunctionId_e": { + "_source": "inav/src/main/io/ledstrip.h", + "LED_FUNCTION_COLOR": "0", + "LED_FUNCTION_FLIGHT_MODE": "1", + "LED_FUNCTION_ARM_STATE": "2", + "LED_FUNCTION_BATTERY": "3", + "LED_FUNCTION_RSSI": "4", + "LED_FUNCTION_GPS": "5", + "LED_FUNCTION_THRUST_RING": "6", + "LED_FUNCTION_CHANNEL": "7" + }, + "ledDirectionId_e": { + "_source": "inav/src/main/io/ledstrip.h", + "LED_DIRECTION_NORTH": "0", + "LED_DIRECTION_EAST": "1", + "LED_DIRECTION_SOUTH": "2", + "LED_DIRECTION_WEST": "3", + "LED_DIRECTION_UP": "4", + "LED_DIRECTION_DOWN": "5" + }, + "ledModeIndex_e": { + "_source": "inav/src/main/io/ledstrip.h", + "LED_MODE_ORIENTATION": "0", + "LED_MODE_HEADFREE": "1", + "LED_MODE_HORIZON": "2", + "LED_MODE_ANGLE": "3", + "LED_MODE_MAG": "4", + "LED_MODE_BARO": "5", + "LED_SPECIAL": "6" + }, + "ledOverlayId_e": { + "_source": "inav/src/main/io/ledstrip.h", + "LED_OVERLAY_THROTTLE": "0", + "LED_OVERLAY_LARSON_SCANNER": "1", + "LED_OVERLAY_BLINK": "2", + "LED_OVERLAY_LANDING_FLASH": "3", + "LED_OVERLAY_INDICATOR": "4", + "LED_OVERLAY_WARNING": "5", + "LED_OVERLAY_STROBE": "6" + }, + "ledSpecialColorIds_e": { + "_source": "inav/src/main/io/ledstrip.h", + "LED_SCOLOR_DISARMED": "0", + "LED_SCOLOR_ARMED": "1", + "LED_SCOLOR_ANIMATION": "2", + "LED_SCOLOR_BACKGROUND": "3", + "LED_SCOLOR_BLINKBACKGROUND": "4", + "LED_SCOLOR_GPSNOSATS": "5", + "LED_SCOLOR_GPSNOLOCK": "6", + "LED_SCOLOR_GPSLOCKED": "7", + "LED_SCOLOR_STROBE": "8" + }, + "logicConditionFlags_e": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_FLAG_LATCH": "1 << 0", + "LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED": "1 << 1" + }, + "logicConditionsGlobalFlags_t": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY": "(1 << 0)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE": "(1 << 1)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW": "(1 << 2)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL": "(1 << 3)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH": "(1 << 4)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW": "(1 << 5)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE": "(1 << 6)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT": "(1 << 7)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL": "(1 << 8)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS": "(1 << 9)", + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_FLIGHT_AXIS": "(1 << 10)", + "LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX": [ + "(1 << 11)", + "USE_GPS_FIX_ESTIMATION" + ], + "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_MIN_GROUND_SPEED": "(1 << 12)" + }, + "logicFlightModeOperands_e": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_FAILSAFE": "0", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_MANUAL": "1", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_RTH": "2", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_POSHOLD": "3", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE": "4", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD": "5", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLE": "6", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_HORIZON": "7", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR": "8", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1": "9", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER2": "10", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD": "11", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3": "12", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4": "13", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO": "14", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION": "15", + "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD": "16" + }, + "logicFlightOperands_e": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER": "0", + "LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE": "1", + "LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE": "2", + "LOGIC_CONDITION_OPERAND_FLIGHT_RSSI": "3", + "LOGIC_CONDITION_OPERAND_FLIGHT_VBAT": "4", + "LOGIC_CONDITION_OPERAND_FLIGHT_CELL_VOLTAGE": "5", + "LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT": "6", + "LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN": "7", + "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_SATS": "8", + "LOGIC_CONDITION_OPERAND_FLIGHT_GROUD_SPEED": "9", + "LOGIC_CONDITION_OPERAND_FLIGHT_3D_SPEED": "10", + "LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED": "11", + "LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE": "12", + "LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED": "13", + "LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS": "14", + "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_ROLL": "15", + "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_PITCH": "16", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED": "17", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH": "18", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL": "19", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL": "20", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING": "21", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH": "22", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING": "23", + "LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE": "24", + "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL": "25", + "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH": "26", + "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW": "27", + "LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE": "28", + "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_UPLINK": "29", + "LOGIC_CONDITION_OPERAND_FLIGHT_SNR": "30", + "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID": "31", + "LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS": "32", + "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE": "33", + "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_CELLS": "34", + "LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS": "35", + "LOGIC_CONDITION_OPERAND_FLIGHT_AGL": "36", + "LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW": "37", + "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE": "38", + "LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE": "39", + "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW": "40", + "LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE": "41", + "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE": "42", + "LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS": "43", + "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK": "44", + "LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM": "45", + "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" + }, + "logicOperandType_e": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_OPERAND_TYPE_VALUE": "0", + "LOGIC_CONDITION_OPERAND_TYPE_RC_CHANNEL": "1", + "LOGIC_CONDITION_OPERAND_TYPE_FLIGHT": "2", + "LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE": "3", + "LOGIC_CONDITION_OPERAND_TYPE_LC": "4", + "LOGIC_CONDITION_OPERAND_TYPE_GVAR": "5", + "LOGIC_CONDITION_OPERAND_TYPE_PID": "6", + "LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS": "7", + "LOGIC_CONDITION_OPERAND_TYPE_LAST": "8" + }, + "logicOperation_e": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_TRUE": "0", + "LOGIC_CONDITION_EQUAL": "1", + "LOGIC_CONDITION_GREATER_THAN": "2", + "LOGIC_CONDITION_LOWER_THAN": "3", + "LOGIC_CONDITION_LOW": "4", + "LOGIC_CONDITION_MID": "5", + "LOGIC_CONDITION_HIGH": "6", + "LOGIC_CONDITION_AND": "7", + "LOGIC_CONDITION_OR": "8", + "LOGIC_CONDITION_XOR": "9", + "LOGIC_CONDITION_NAND": "10", + "LOGIC_CONDITION_NOR": "11", + "LOGIC_CONDITION_NOT": "12", + "LOGIC_CONDITION_STICKY": "13", + "LOGIC_CONDITION_ADD": "14", + "LOGIC_CONDITION_SUB": "15", + "LOGIC_CONDITION_MUL": "16", + "LOGIC_CONDITION_DIV": "17", + "LOGIC_CONDITION_GVAR_SET": "18", + "LOGIC_CONDITION_GVAR_INC": "19", + "LOGIC_CONDITION_GVAR_DEC": "20", + "LOGIC_CONDITION_PORT_SET": "21", + "LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY": "22", + "LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE": "23", + "LOGIC_CONDITION_SWAP_ROLL_YAW": "24", + "LOGIC_CONDITION_SET_VTX_POWER_LEVEL": "25", + "LOGIC_CONDITION_INVERT_ROLL": "26", + "LOGIC_CONDITION_INVERT_PITCH": "27", + "LOGIC_CONDITION_INVERT_YAW": "28", + "LOGIC_CONDITION_OVERRIDE_THROTTLE": "29", + "LOGIC_CONDITION_SET_VTX_BAND": "30", + "LOGIC_CONDITION_SET_VTX_CHANNEL": "31", + "LOGIC_CONDITION_SET_OSD_LAYOUT": "32", + "LOGIC_CONDITION_SIN": "33", + "LOGIC_CONDITION_COS": "34", + "LOGIC_CONDITION_TAN": "35", + "LOGIC_CONDITION_MAP_INPUT": "36", + "LOGIC_CONDITION_MAP_OUTPUT": "37", + "LOGIC_CONDITION_RC_CHANNEL_OVERRIDE": "38", + "LOGIC_CONDITION_SET_HEADING_TARGET": "39", + "LOGIC_CONDITION_MODULUS": "40", + "LOGIC_CONDITION_LOITER_OVERRIDE": "41", + "LOGIC_CONDITION_SET_PROFILE": "42", + "LOGIC_CONDITION_MIN": "43", + "LOGIC_CONDITION_MAX": "44", + "LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE": "45", + "LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE": "46", + "LOGIC_CONDITION_EDGE": "47", + "LOGIC_CONDITION_DELAY": "48", + "LOGIC_CONDITION_TIMER": "49", + "LOGIC_CONDITION_DELTA": "50", + "LOGIC_CONDITION_APPROX_EQUAL": "51", + "LOGIC_CONDITION_LED_PIN_PWM": "52", + "LOGIC_CONDITION_DISABLE_GPS_FIX": "53", + "LOGIC_CONDITION_RESET_MAG_CALIBRATION": "54", + "LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY": "55", + "LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED": "56", + "LOGIC_CONDITION_LAST": "57" + }, + "logicWaypointOperands_e": { + "_source": "inav/src/main/programming/logic_condition.h", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_IS_WP": "0", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_INDEX": "1", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_ACTION": "2", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_NEXT_WAYPOINT_ACTION": "3", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_DISTANCE": "4", + "LOGIC_CONDTIION_OPERAND_WAYPOINTS_DISTANCE_FROM_WAYPOINT": "5", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION": "6", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION": "7", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION": "8", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION": "9", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION_NEXT_WP": "10", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION_NEXT_WP": "11", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION_NEXT_WP": "12", + "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION_NEXT_WP": "13" + }, + "logTopic_e": { + "_source": "inav/src/main/common/log.h", + "LOG_TOPIC_SYSTEM": "0", + "LOG_TOPIC_GYRO": "1", + "LOG_TOPIC_BARO": "2", + "LOG_TOPIC_PITOT": "3", + "LOG_TOPIC_PWM": "4", + "LOG_TOPIC_TIMER": "5", + "LOG_TOPIC_IMU": "6", + "LOG_TOPIC_TEMPERATURE": "7", + "LOG_TOPIC_POS_ESTIMATOR": "8", + "LOG_TOPIC_VTX": "9", + "LOG_TOPIC_OSD": "10", + "LOG_TOPIC_COUNT": "11" + }, + "lsm6dxxConfigMasks_e": { + "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", + "LSM6DXX_MASK_COUNTER_BDR1": "128", + "LSM6DXX_MASK_CTRL3_C": "60", + "LSM6DXX_MASK_CTRL3_C_RESET": "BIT(0)", + "LSM6DXX_MASK_CTRL4_C": "14", + "LSM6DXX_MASK_CTRL6_C": "23", + "LSM6DXX_MASK_CTRL7_G": "112", + "LSM6DXX_MASK_CTRL9_XL": "2", + "LSM6DSL_MASK_CTRL6_C": "19" + }, + "lsm6dxxConfigValues_e": { + "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", + "LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM": "BIT(7)", + "LSM6DXX_VAL_INT1_CTRL": "2", + "LSM6DXX_VAL_INT2_CTRL": "0", + "LSM6DXX_VAL_CTRL1_XL_ODR833": "7", + "LSM6DXX_VAL_CTRL1_XL_ODR1667": "8", + "LSM6DXX_VAL_CTRL1_XL_ODR3332": "9", + "LSM6DXX_VAL_CTRL1_XL_ODR3333": "10", + "LSM6DXX_VAL_CTRL1_XL_8G": "3", + "LSM6DXX_VAL_CTRL1_XL_16G": "1", + "LSM6DXX_VAL_CTRL1_XL_LPF1": "0", + "LSM6DXX_VAL_CTRL1_XL_LPF2": "1", + "LSM6DXX_VAL_CTRL2_G_ODR6664": "10", + "LSM6DXX_VAL_CTRL2_G_2000DPS": "3", + "LSM6DXX_VAL_CTRL3_C_H_LACTIVE": "0", + "LSM6DXX_VAL_CTRL3_C_PP_OD": "0", + "LSM6DXX_VAL_CTRL3_C_SIM": "0", + "LSM6DXX_VAL_CTRL3_C_IF_INC": "BIT(2)", + "LSM6DXX_VAL_CTRL4_C_DRDY_MASK": "BIT(3)", + "LSM6DXX_VAL_CTRL4_C_I2C_DISABLE": "BIT(2)", + "LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G": "BIT(1)", + "LSM6DXX_VAL_CTRL6_C_XL_HM_MODE": "0", + "LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ": "0", + "LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ": "1", + "LSM6DXX_VAL_CTRL6_C_FTYPE_102HZ": "2", + "LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ": "3", + "LSM6DXX_VAL_CTRL7_G_HP_EN_G": "BIT(6)", + "LSM6DXX_VAL_CTRL7_G_HPM_G_16": "0", + "LSM6DXX_VAL_CTRL7_G_HPM_G_65": "1", + "LSM6DXX_VAL_CTRL7_G_HPM_G_260": "2", + "LSM6DXX_VAL_CTRL7_G_HPM_G_1040": "3", + "LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE": "BIT(1)" + }, + "lsm6dxxRegister_e": { + "_source": "inav/src/main/drivers/accgyro/accgyro_lsm6dxx.h", + "LSM6DXX_REG_COUNTER_BDR1": "11", + "LSM6DXX_REG_INT1_CTRL": "13", + "LSM6DXX_REG_INT2_CTRL": "14", + "LSM6DXX_REG_WHO_AM_I": "15", + "LSM6DXX_REG_CTRL1_XL": "16", + "LSM6DXX_REG_CTRL2_G": "17", + "LSM6DXX_REG_CTRL3_C": "18", + "LSM6DXX_REG_CTRL4_C": "19", + "LSM6DXX_REG_CTRL5_C": "20", + "LSM6DXX_REG_CTRL6_C": "21", + "LSM6DXX_REG_CTRL7_G": "22", + "LSM6DXX_REG_CTRL8_XL": "23", + "LSM6DXX_REG_CTRL9_XL": "24", + "LSM6DXX_REG_CTRL10_C": "25", + "LSM6DXX_REG_STATUS": "30", + "LSM6DXX_REG_OUT_TEMP_L": "32", + "LSM6DXX_REG_OUT_TEMP_H": "33", + "LSM6DXX_REG_OUTX_L_G": "34", + "LSM6DXX_REG_OUTX_H_G": "35", + "LSM6DXX_REG_OUTY_L_G": "36", + "LSM6DXX_REG_OUTY_H_G": "37", + "LSM6DXX_REG_OUTZ_L_G": "38", + "LSM6DXX_REG_OUTZ_H_G": "39", + "LSM6DXX_REG_OUTX_L_A": "40", + "LSM6DXX_REG_OUTX_H_A": "41", + "LSM6DXX_REG_OUTY_L_A": "42", + "LSM6DXX_REG_OUTY_H_A": "43", + "LSM6DXX_REG_OUTZ_L_A": "44", + "LSM6DXX_REG_OUTZ_H_A": "45" + }, + "ltm_frame_e": { + "_source": "inav/src/main/telemetry/ltm.h", + "LTM_FRAME_START": "0", + "LTM_AFRAME": "LTM_FRAME_START", + "LTM_SFRAME": "", + "LTM_GFRAME": [ + "", + "USE_GPS" + ], + "LTM_OFRAME": [ + "", + "USE_GPS" + ], + "LTM_XFRAME": [ + "", + "USE_GPS" + ], + "LTM_NFRAME": "", + "LTM_FRAME_COUNT": "" + }, + "ltm_modes_e": { + "_source": "inav/src/main/telemetry/ltm.h", + "LTM_MODE_MANUAL": "0", + "LTM_MODE_RATE": "1", + "LTM_MODE_ANGLE": "2", + "LTM_MODE_HORIZON": "3", + "LTM_MODE_ACRO": "4", + "LTM_MODE_STABALIZED1": "5", + "LTM_MODE_STABALIZED2": "6", + "LTM_MODE_STABILIZED3": "7", + "LTM_MODE_ALTHOLD": "8", + "LTM_MODE_GPSHOLD": "9", + "LTM_MODE_WAYPOINTS": "10", + "LTM_MODE_HEADHOLD": "11", + "LTM_MODE_CIRCLE": "12", + "LTM_MODE_RTH": "13", + "LTM_MODE_FOLLOWWME": "14", + "LTM_MODE_LAND": "15", + "LTM_MODE_FLYBYWIRE1": "16", + "LTM_MODE_FLYBYWIRE2": "17", + "LTM_MODE_CRUISE": "18", + "LTM_MODE_UNKNOWN": "19", + "LTM_MODE_LAUNCH": "20", + "LTM_MODE_AUTOTUNE": "21" + }, + "ltmUpdateRate_e": { + "_source": "inav/src/main/telemetry/telemetry.h", + "LTM_RATE_NORMAL": "0", + "LTM_RATE_MEDIUM": "1", + "LTM_RATE_SLOW": "2" + }, + "magSensor_e": { + "_source": "inav/src/main/sensors/compass.h", + "MAG_NONE": "0", + "MAG_AUTODETECT": "1", + "MAG_HMC5883": "2", + "MAG_AK8975": "3", + "MAG_MAG3110": "4", + "MAG_AK8963": "5", + "MAG_IST8310": "6", + "MAG_QMC5883": "7", + "MAG_QMC5883P": "8", + "MAG_MPU9250": "9", + "MAG_IST8308": "10", + "MAG_LIS3MDL": "11", + "MAG_MSP": "12", + "MAG_RM3100": "13", + "MAG_VCM5883": "14", + "MAG_MLX90393": "15", + "MAG_FAKE": "16", + "MAG_MAX": "MAG_FAKE" + }, + "mavlinkAutopilotType_e": { + "_source": "inav/src/main/telemetry/telemetry.h", + "MAVLINK_AUTOPILOT_GENERIC": "0", + "MAVLINK_AUTOPILOT_ARDUPILOT": "1" + }, + "mavlinkRadio_e": { + "_source": "inav/src/main/telemetry/telemetry.h", + "MAVLINK_RADIO_GENERIC": "0", + "MAVLINK_RADIO_ELRS": "1", + "MAVLINK_RADIO_SIK": "2" + }, + "measurementSteps_e": { + "_source": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c", + "MEASUREMENT_START": "0", + "MEASUREMENT_WAIT": "1", + "MEASUREMENT_READ": "2" + }, + "mixerProfileATRequest_e": { + "_source": "inav/src/main/flight/mixer_profile.h", + "MIXERAT_REQUEST_NONE": "0", + "MIXERAT_REQUEST_RTH": "1", + "MIXERAT_REQUEST_LAND": "2", + "MIXERAT_REQUEST_ABORT": "3" + }, + "mixerProfileATState_e": { + "_source": "inav/src/main/flight/mixer_profile.h", + "MIXERAT_PHASE_IDLE": "0", + "MIXERAT_PHASE_TRANSITION_INITIALIZE": "1", + "MIXERAT_PHASE_TRANSITIONING": "2", + "MIXERAT_PHASE_DONE": "3" + }, + "modeActivationOperator_e": { + "_source": "inav/src/main/fc/rc_modes.h", + "MODE_OPERATOR_OR": "0", + "MODE_OPERATOR_AND": "1" + }, + "motorPwmProtocolTypes_e": { + "_source": "inav/src/main/drivers/pwm_mapping.h", + "PWM_TYPE_STANDARD": "0", + "PWM_TYPE_ONESHOT125": "1", + "PWM_TYPE_MULTISHOT": "2", + "PWM_TYPE_BRUSHED": "3", + "PWM_TYPE_DSHOT150": "4", + "PWM_TYPE_DSHOT300": "5", + "PWM_TYPE_DSHOT600": "6" + }, + "motorStatus_e": { + "_source": "inav/src/main/flight/mixer.h", + "MOTOR_STOPPED_USER": "0", + "MOTOR_STOPPED_AUTO": "1", + "MOTOR_RUNNING": "2" + }, + "mpu9250CompassReadState_e": { + "_source": "inav/src/main/drivers/compass/compass_mpu9250.c", + "CHECK_STATUS": "0", + "WAITING_FOR_STATUS": "1", + "WAITING_FOR_DATA": "2" + }, + "mspFlashfsFlags_e": { + "_source": "inav/src/main/fc/fc_msp.c", + "MSP_FLASHFS_BIT_READY": "1", + "MSP_FLASHFS_BIT_SUPPORTED": "2" + }, + "mspPassthroughType_e": { + "_source": "inav/src/main/fc/fc_msp.c", + "MSP_PASSTHROUGH_SERIAL_ID": "253", + "MSP_PASSTHROUGH_SERIAL_FUNCTION_ID": "254", + "MSP_PASSTHROUGH_ESC_4WAY": "255" + }, + "mspSDCardFlags_e": { + "_source": "inav/src/main/fc/fc_msp.c", + "MSP_SDCARD_FLAG_SUPPORTTED": "1" + }, + "mspSDCardState_e": { + "_source": "inav/src/main/fc/fc_msp.c", + "MSP_SDCARD_STATE_NOT_PRESENT": "0", + "MSP_SDCARD_STATE_FATAL": "1", + "MSP_SDCARD_STATE_CARD_INIT": "2", + "MSP_SDCARD_STATE_FS_INIT": "3", + "MSP_SDCARD_STATE_READY": "4" + }, + "multi_function_e": { + "_source": "inav/src/main/fc/multifunction.h", + "MULTI_FUNC_NONE": "0", + "MULTI_FUNC_1": "1", + "MULTI_FUNC_2": "2", + "MULTI_FUNC_3": "3", + "MULTI_FUNC_4": "4", + "MULTI_FUNC_5": "5", + "MULTI_FUNC_6": "6", + "MULTI_FUNC_END": "7" + }, + "multiFunctionFlags_e": { + "_source": "inav/src/main/fc/multifunction.h", + "MF_SUSPEND_SAFEHOMES": "(1 << 0)", + "MF_SUSPEND_TRACKBACK": "(1 << 1)", + "MF_TURTLE_MODE": "(1 << 2)" + }, + "nav_reset_type_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_RESET_NEVER": "0", + "NAV_RESET_ON_FIRST_ARM": "1", + "NAV_RESET_ON_EACH_ARM": "2" + }, + "navAGLEstimateQuality_e": { + "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h", + "SURFACE_QUAL_LOW": "0", + "SURFACE_QUAL_MID": "1", + "SURFACE_QUAL_HIGH": "2" + }, + "navArmingBlocker_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_ARMING_BLOCKER_NONE": "0", + "NAV_ARMING_BLOCKER_MISSING_GPS_FIX": "1", + "NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE": "2", + "NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR": "3", + "NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR": "4" + }, + "navDefaultAltitudeSensor_e": { + "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h", + "ALTITUDE_SOURCE_GPS": "0", + "ALTITUDE_SOURCE_BARO": "1", + "ALTITUDE_SOURCE_GPS_ONLY": "2", + "ALTITUDE_SOURCE_BARO_ONLY": "3" + }, + "navExtraArmingSafety_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_EXTRA_ARMING_SAFETY_ON": "0", + "NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS": "1" + }, + "navFwLaunchStatus_e": { + "_source": "inav/src/main/navigation/navigation.h", + "FW_LAUNCH_DETECTED": "5", + "FW_LAUNCH_ABORTED": "10", + "FW_LAUNCH_FLYING": "11" + }, + "navigationEstimateStatus_e": { + "_source": "inav/src/main/navigation/navigation_private.h", + "EST_NONE": "0", + "EST_USABLE": "1", + "EST_TRUSTED": "2" + }, + "navigationFSMEvent_t": { + "_source": "inav/src/main/navigation/navigation_private.h", + "NAV_FSM_EVENT_NONE": "0", + "NAV_FSM_EVENT_TIMEOUT": "1", + "NAV_FSM_EVENT_SUCCESS": "2", + "NAV_FSM_EVENT_ERROR": "3", + "NAV_FSM_EVENT_SWITCH_TO_IDLE": "4", + "NAV_FSM_EVENT_SWITCH_TO_ALTHOLD": "5", + "NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D": "6", + "NAV_FSM_EVENT_SWITCH_TO_RTH": "7", + "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT": "8", + "NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING": "9", + "NAV_FSM_EVENT_SWITCH_TO_LAUNCH": "10", + "NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD": "11", + "NAV_FSM_EVENT_SWITCH_TO_CRUISE": "12", + "NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ": "13", + "NAV_FSM_EVENT_SWITCH_TO_MIXERAT": "14", + "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING": "15", + "NAV_FSM_EVENT_SWITCH_TO_SEND_TO": "16", + "NAV_FSM_EVENT_STATE_SPECIFIC_1": "17", + "NAV_FSM_EVENT_STATE_SPECIFIC_2": "18", + "NAV_FSM_EVENT_STATE_SPECIFIC_3": "19", + "NAV_FSM_EVENT_STATE_SPECIFIC_4": "20", + "NAV_FSM_EVENT_STATE_SPECIFIC_5": "21", + "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_ABORT": "NAV_FSM_EVENT_STATE_SPECIFIC_1", + "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_2", + "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_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", + "NAV_FSM_EVENT_SWITCH_TO_RTH_LOITER_ABOVE_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_4", + "NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING": "NAV_FSM_EVENT_STATE_SPECIFIC_5", + "NAV_FSM_EVENT_COUNT": "" + }, + "navigationFSMState_t": { + "_source": "inav/src/main/navigation/navigation_private.h", + "NAV_STATE_UNDEFINED": "0", + "NAV_STATE_IDLE": "1", + "NAV_STATE_ALTHOLD_INITIALIZE": "2", + "NAV_STATE_ALTHOLD_IN_PROGRESS": "3", + "NAV_STATE_POSHOLD_3D_INITIALIZE": "4", + "NAV_STATE_POSHOLD_3D_IN_PROGRESS": "5", + "NAV_STATE_RTH_INITIALIZE": "6", + "NAV_STATE_RTH_CLIMB_TO_SAFE_ALT": "7", + "NAV_STATE_RTH_TRACKBACK": "8", + "NAV_STATE_RTH_HEAD_HOME": "9", + "NAV_STATE_RTH_LOITER_PRIOR_TO_LANDING": "10", + "NAV_STATE_RTH_LOITER_ABOVE_HOME": "11", + "NAV_STATE_RTH_LANDING": "12", + "NAV_STATE_RTH_FINISHING": "13", + "NAV_STATE_RTH_FINISHED": "14", + "NAV_STATE_WAYPOINT_INITIALIZE": "15", + "NAV_STATE_WAYPOINT_PRE_ACTION": "16", + "NAV_STATE_WAYPOINT_IN_PROGRESS": "17", + "NAV_STATE_WAYPOINT_REACHED": "18", + "NAV_STATE_WAYPOINT_HOLD_TIME": "19", + "NAV_STATE_WAYPOINT_NEXT": "20", + "NAV_STATE_WAYPOINT_FINISHED": "21", + "NAV_STATE_WAYPOINT_RTH_LAND": "22", + "NAV_STATE_EMERGENCY_LANDING_INITIALIZE": "23", + "NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS": "24", + "NAV_STATE_EMERGENCY_LANDING_FINISHED": "25", + "NAV_STATE_LAUNCH_INITIALIZE": "26", + "NAV_STATE_LAUNCH_WAIT": "27", + "NAV_STATE_LAUNCH_IN_PROGRESS": "28", + "NAV_STATE_COURSE_HOLD_INITIALIZE": "29", + "NAV_STATE_COURSE_HOLD_IN_PROGRESS": "30", + "NAV_STATE_COURSE_HOLD_ADJUSTING": "31", + "NAV_STATE_CRUISE_INITIALIZE": "32", + "NAV_STATE_CRUISE_IN_PROGRESS": "33", + "NAV_STATE_CRUISE_ADJUSTING": "34", + "NAV_STATE_FW_LANDING_CLIMB_TO_LOITER": "35", + "NAV_STATE_FW_LANDING_LOITER": "36", + "NAV_STATE_FW_LANDING_APPROACH": "37", + "NAV_STATE_FW_LANDING_GLIDE": "38", + "NAV_STATE_FW_LANDING_FLARE": "39", + "NAV_STATE_FW_LANDING_FINISHED": "40", + "NAV_STATE_FW_LANDING_ABORT": "41", + "NAV_STATE_MIXERAT_INITIALIZE": "42", + "NAV_STATE_MIXERAT_IN_PROGRESS": "43", + "NAV_STATE_MIXERAT_ABORT": "44", + "NAV_STATE_SEND_TO_INITALIZE": "45", + "NAV_STATE_SEND_TO_IN_PROGESS": "46", + "NAV_STATE_SEND_TO_FINISHED": "47", + "NAV_STATE_COUNT": "48" + }, + "navigationFSMStateFlags_t": { + "_source": "inav/src/main/navigation/navigation_private.h", + "NAV_CTL_ALT": "(1 << 0)", + "NAV_CTL_POS": "(1 << 1)", + "NAV_CTL_YAW": "(1 << 2)", + "NAV_CTL_EMERG": "(1 << 3)", + "NAV_CTL_LAUNCH": "(1 << 4)", + "NAV_REQUIRE_ANGLE": "(1 << 5)", + "NAV_REQUIRE_ANGLE_FW": "(1 << 6)", + "NAV_REQUIRE_MAGHOLD": "(1 << 7)", + "NAV_REQUIRE_THRTILT": "(1 << 8)", + "NAV_AUTO_RTH": "(1 << 9)", + "NAV_AUTO_WP": "(1 << 10)", + "NAV_RC_ALT": "(1 << 11)", + "NAV_RC_POS": "(1 << 12)", + "NAV_RC_YAW": "(1 << 13)", + "NAV_CTL_LAND": "(1 << 14)", + "NAV_AUTO_WP_DONE": "(1 << 15)", + "NAV_MIXERAT": "(1 << 16)", + "NAV_CTL_HOLD": "(1 << 17)" + }, + "navigationHomeFlags_t": { + "_source": "inav/src/main/navigation/navigation_private.h", + "NAV_HOME_INVALID": "0", + "NAV_HOME_VALID_XY": "1 << 0", + "NAV_HOME_VALID_Z": "1 << 1", + "NAV_HOME_VALID_HEADING": "1 << 2", + "NAV_HOME_VALID_ALL": "NAV_HOME_VALID_XY | NAV_HOME_VALID_Z | NAV_HOME_VALID_HEADING" + }, + "navigationPersistentId_e": { + "_source": "inav/src/main/navigation/navigation_private.h", + "NAV_PERSISTENT_ID_UNDEFINED": "0", + "NAV_PERSISTENT_ID_IDLE": "1", + "NAV_PERSISTENT_ID_ALTHOLD_INITIALIZE": "2", + "NAV_PERSISTENT_ID_ALTHOLD_IN_PROGRESS": "3", + "NAV_PERSISTENT_ID_UNUSED_1": "4", + "NAV_PERSISTENT_ID_UNUSED_2": "5", + "NAV_PERSISTENT_ID_POSHOLD_3D_INITIALIZE": "6", + "NAV_PERSISTENT_ID_POSHOLD_3D_IN_PROGRESS": "7", + "NAV_PERSISTENT_ID_RTH_INITIALIZE": "8", + "NAV_PERSISTENT_ID_RTH_CLIMB_TO_SAFE_ALT": "9", + "NAV_PERSISTENT_ID_RTH_HEAD_HOME": "10", + "NAV_PERSISTENT_ID_RTH_LOITER_PRIOR_TO_LANDING": "11", + "NAV_PERSISTENT_ID_RTH_LANDING": "12", + "NAV_PERSISTENT_ID_RTH_FINISHING": "13", + "NAV_PERSISTENT_ID_RTH_FINISHED": "14", + "NAV_PERSISTENT_ID_WAYPOINT_INITIALIZE": "15", + "NAV_PERSISTENT_ID_WAYPOINT_PRE_ACTION": "16", + "NAV_PERSISTENT_ID_WAYPOINT_IN_PROGRESS": "17", + "NAV_PERSISTENT_ID_WAYPOINT_REACHED": "18", + "NAV_PERSISTENT_ID_WAYPOINT_NEXT": "19", + "NAV_PERSISTENT_ID_WAYPOINT_FINISHED": "20", + "NAV_PERSISTENT_ID_WAYPOINT_RTH_LAND": "21", + "NAV_PERSISTENT_ID_EMERGENCY_LANDING_INITIALIZE": "22", + "NAV_PERSISTENT_ID_EMERGENCY_LANDING_IN_PROGRESS": "23", + "NAV_PERSISTENT_ID_EMERGENCY_LANDING_FINISHED": "24", + "NAV_PERSISTENT_ID_LAUNCH_INITIALIZE": "25", + "NAV_PERSISTENT_ID_LAUNCH_WAIT": "26", + "NAV_PERSISTENT_ID_UNUSED_3": "27", + "NAV_PERSISTENT_ID_LAUNCH_IN_PROGRESS": "28", + "NAV_PERSISTENT_ID_COURSE_HOLD_INITIALIZE": "29", + "NAV_PERSISTENT_ID_COURSE_HOLD_IN_PROGRESS": "30", + "NAV_PERSISTENT_ID_COURSE_HOLD_ADJUSTING": "31", + "NAV_PERSISTENT_ID_CRUISE_INITIALIZE": "32", + "NAV_PERSISTENT_ID_CRUISE_IN_PROGRESS": "33", + "NAV_PERSISTENT_ID_CRUISE_ADJUSTING": "34", + "NAV_PERSISTENT_ID_WAYPOINT_HOLD_TIME": "35", + "NAV_PERSISTENT_ID_RTH_LOITER_ABOVE_HOME": "36", + "NAV_PERSISTENT_ID_UNUSED_4": "37", + "NAV_PERSISTENT_ID_RTH_TRACKBACK": "38", + "NAV_PERSISTENT_ID_MIXERAT_INITIALIZE": "39", + "NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS": "40", + "NAV_PERSISTENT_ID_MIXERAT_ABORT": "41", + "NAV_PERSISTENT_ID_FW_LANDING_CLIMB_TO_LOITER": "42", + "NAV_PERSISTENT_ID_FW_LANDING_LOITER": "43", + "NAV_PERSISTENT_ID_FW_LANDING_APPROACH": "44", + "NAV_PERSISTENT_ID_FW_LANDING_GLIDE": "45", + "NAV_PERSISTENT_ID_FW_LANDING_FLARE": "46", + "NAV_PERSISTENT_ID_FW_LANDING_ABORT": "47", + "NAV_PERSISTENT_ID_FW_LANDING_FINISHED": "48", + "NAV_PERSISTENT_ID_SEND_TO_INITALIZE": "49", + "NAV_PERSISTENT_ID_SEND_TO_IN_PROGRES": "50", + "NAV_PERSISTENT_ID_SEND_TO_FINISHED": "51" + }, + "navMcAltHoldThrottle_e": { + "_source": "inav/src/main/navigation/navigation.h", + "MC_ALT_HOLD_STICK": "0", + "MC_ALT_HOLD_MID": "1", + "MC_ALT_HOLD_HOVER": "2" + }, + "navMissionRestart_e": { + "_source": "inav/src/main/navigation/navigation.h", + "WP_MISSION_START": "0", + "WP_MISSION_RESUME": "1", + "WP_MISSION_SWITCH": "2" + }, + "navOverridesMotorStop_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NOMS_OFF_ALWAYS": "0", + "NOMS_OFF": "1", + "NOMS_AUTO_ONLY": "2", + "NOMS_ALL_NAV": "3" + }, + "navPositionEstimationFlags_e": { + "_source": "inav/src/main/navigation/navigation_pos_estimator_private.h", + "EST_GPS_XY_VALID": "(1 << 0)", + "EST_GPS_Z_VALID": "(1 << 1)", + "EST_BARO_VALID": "(1 << 2)", + "EST_SURFACE_VALID": "(1 << 3)", + "EST_FLOW_VALID": "(1 << 4)", + "EST_XY_VALID": "(1 << 5)", + "EST_Z_VALID": "(1 << 6)" + }, + "navRTHAllowLanding_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_RTH_ALLOW_LANDING_NEVER": "0", + "NAV_RTH_ALLOW_LANDING_ALWAYS": "1", + "NAV_RTH_ALLOW_LANDING_FS_ONLY": "2" + }, + "navRTHClimbFirst_e": { + "_source": "inav/src/main/navigation/navigation.h", + "RTH_CLIMB_OFF": "0", + "RTH_CLIMB_ON": "1", + "RTH_CLIMB_ON_FW_SPIRAL": "2" + }, + "navSetWaypointFlags_t": { + "_source": "inav/src/main/navigation/navigation_private.h", + "NAV_POS_UPDATE_NONE": "0", + "NAV_POS_UPDATE_Z": "1 << 1", + "NAV_POS_UPDATE_XY": "1 << 0", + "NAV_POS_UPDATE_HEADING": "1 << 2", + "NAV_POS_UPDATE_BEARING": "1 << 3", + "NAV_POS_UPDATE_BEARING_TAIL_FIRST": "1 << 4" + }, + "navSystemStatus_Error_e": { + "_source": "inav/src/main/navigation/navigation.h", + "MW_NAV_ERROR_NONE": "0", + "MW_NAV_ERROR_TOOFAR": "1", + "MW_NAV_ERROR_SPOILED_GPS": "2", + "MW_NAV_ERROR_WP_CRC": "3", + "MW_NAV_ERROR_FINISH": "4", + "MW_NAV_ERROR_TIMEWAIT": "5", + "MW_NAV_ERROR_INVALID_JUMP": "6", + "MW_NAV_ERROR_INVALID_DATA": "7", + "MW_NAV_ERROR_WAIT_FOR_RTH_ALT": "8", + "MW_NAV_ERROR_GPS_FIX_LOST": "9", + "MW_NAV_ERROR_DISARMED": "10", + "MW_NAV_ERROR_LANDING": "11" + }, + "navSystemStatus_Flags_e": { + "_source": "inav/src/main/navigation/navigation.h", + "MW_NAV_FLAG_ADJUSTING_POSITION": "1 << 0", + "MW_NAV_FLAG_ADJUSTING_ALTITUDE": "1 << 1" + }, + "navSystemStatus_Mode_e": { + "_source": "inav/src/main/navigation/navigation.h", + "MW_GPS_MODE_NONE": "0", + "MW_GPS_MODE_HOLD": "1", + "MW_GPS_MODE_RTH": "2", + "MW_GPS_MODE_NAV": "3", + "MW_GPS_MODE_EMERG": "15" + }, + "navSystemStatus_State_e": { + "_source": "inav/src/main/navigation/navigation.h", + "MW_NAV_STATE_NONE": "0", + "MW_NAV_STATE_RTH_START": "1", + "MW_NAV_STATE_RTH_ENROUTE": "2", + "MW_NAV_STATE_HOLD_INFINIT": "3", + "MW_NAV_STATE_HOLD_TIMED": "4", + "MW_NAV_STATE_WP_ENROUTE": "5", + "MW_NAV_STATE_PROCESS_NEXT": "6", + "MW_NAV_STATE_DO_JUMP": "7", + "MW_NAV_STATE_LAND_START": "8", + "MW_NAV_STATE_LAND_IN_PROGRESS": "9", + "MW_NAV_STATE_LANDED": "10", + "MW_NAV_STATE_LAND_SETTLE": "11", + "MW_NAV_STATE_LAND_START_DESCENT": "12", + "MW_NAV_STATE_HOVER_ABOVE_HOME": "13", + "MW_NAV_STATE_EMERGENCY_LANDING": "14", + "MW_NAV_STATE_RTH_CLIMB": "15" + }, + "navWaypointActions_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_WP_ACTION_WAYPOINT": "1", + "NAV_WP_ACTION_HOLD_TIME": "3", + "NAV_WP_ACTION_RTH": "4", + "NAV_WP_ACTION_SET_POI": "5", + "NAV_WP_ACTION_JUMP": "6", + "NAV_WP_ACTION_SET_HEAD": "7", + "NAV_WP_ACTION_LAND": "8" + }, + "navWaypointFlags_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_WP_FLAG_HOME": "72", + "NAV_WP_FLAG_LAST": "165" + }, + "navWaypointHeadings_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_WP_HEAD_MODE_NONE": "0", + "NAV_WP_HEAD_MODE_POI": "1", + "NAV_WP_HEAD_MODE_FIXED": "2" + }, + "navWaypointP3Flags_e": { + "_source": "inav/src/main/navigation/navigation.h", + "NAV_WP_ALTMODE": "(1<<0)", + "NAV_WP_USER1": "(1<<1)", + "NAV_WP_USER2": "(1<<2)", + "NAV_WP_USER3": "(1<<3)", + "NAV_WP_USER4": "(1<<4)" + }, + "opflowQuality_e": { + "_source": "inav/src/main/sensors/opflow.h", + "OPFLOW_QUALITY_INVALID": "0", + "OPFLOW_QUALITY_VALID": "1" + }, + "opticalFlowSensor_e": { + "_source": "inav/src/main/sensors/opflow.h", + "OPFLOW_NONE": "0", + "OPFLOW_CXOF": "1", + "OPFLOW_MSP": "2", + "OPFLOW_FAKE": "3" + }, + "osd_adsb_warning_style_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_ADSB_WARNING_STYLE_COMPACT": "0", + "OSD_ADSB_WARNING_STYLE_EXTENDED": "1" + }, + "osd_ahi_style_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_AHI_STYLE_DEFAULT": "0", + "OSD_AHI_STYLE_LINE": "1" + }, + "osd_alignment_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_ALIGN_LEFT": "0", + "OSD_ALIGN_RIGHT": "1" + }, + "osd_crosshairs_style_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_CROSSHAIRS_STYLE_DEFAULT": "0", + "OSD_CROSSHAIRS_STYLE_AIRCRAFT": "1", + "OSD_CROSSHAIRS_STYLE_TYPE3": "2", + "OSD_CROSSHAIRS_STYLE_TYPE4": "3", + "OSD_CROSSHAIRS_STYLE_TYPE5": "4", + "OSD_CROSSHAIRS_STYLE_TYPE6": "5", + "OSD_CROSSHAIRS_STYLE_TYPE7": "6" + }, + "osd_crsf_lq_format_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_CRSF_LQ_TYPE1": "0", + "OSD_CRSF_LQ_TYPE2": "1", + "OSD_CRSF_LQ_TYPE3": "2" + }, + "osd_items_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_RSSI_VALUE": "0", + "OSD_MAIN_BATT_VOLTAGE": "1", + "OSD_CROSSHAIRS": "2", + "OSD_ARTIFICIAL_HORIZON": "3", + "OSD_HORIZON_SIDEBARS": "4", + "OSD_ONTIME": "5", + "OSD_FLYTIME": "6", + "OSD_FLYMODE": "7", + "OSD_CRAFT_NAME": "8", + "OSD_THROTTLE_POS": "9", + "OSD_VTX_CHANNEL": "10", + "OSD_CURRENT_DRAW": "11", + "OSD_MAH_DRAWN": "12", + "OSD_GPS_SPEED": "13", + "OSD_GPS_SATS": "14", + "OSD_ALTITUDE": "15", + "OSD_ROLL_PIDS": "16", + "OSD_PITCH_PIDS": "17", + "OSD_YAW_PIDS": "18", + "OSD_POWER": "19", + "OSD_GPS_LON": "20", + "OSD_GPS_LAT": "21", + "OSD_HOME_DIR": "22", + "OSD_HOME_DIST": "23", + "OSD_HEADING": "24", + "OSD_VARIO": "25", + "OSD_VERTICAL_SPEED_INDICATOR": "26", + "OSD_AIR_SPEED": "27", + "OSD_ONTIME_FLYTIME": "28", + "OSD_RTC_TIME": "29", + "OSD_MESSAGES": "30", + "OSD_GPS_HDOP": "31", + "OSD_MAIN_BATT_CELL_VOLTAGE": "32", + "OSD_SCALED_THROTTLE_POS": "33", + "OSD_HEADING_GRAPH": "34", + "OSD_EFFICIENCY_MAH_PER_KM": "35", + "OSD_WH_DRAWN": "36", + "OSD_BATTERY_REMAINING_CAPACITY": "37", + "OSD_BATTERY_REMAINING_PERCENT": "38", + "OSD_EFFICIENCY_WH_PER_KM": "39", + "OSD_TRIP_DIST": "40", + "OSD_ATTITUDE_PITCH": "41", + "OSD_ATTITUDE_ROLL": "42", + "OSD_MAP_NORTH": "43", + "OSD_MAP_TAKEOFF": "44", + "OSD_RADAR": "45", + "OSD_WIND_SPEED_HORIZONTAL": "46", + "OSD_WIND_SPEED_VERTICAL": "47", + "OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH": "48", + "OSD_REMAINING_DISTANCE_BEFORE_RTH": "49", + "OSD_HOME_HEADING_ERROR": "50", + "OSD_COURSE_HOLD_ERROR": "51", + "OSD_COURSE_HOLD_ADJUSTMENT": "52", + "OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE": "53", + "OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE": "54", + "OSD_POWER_SUPPLY_IMPEDANCE": "55", + "OSD_LEVEL_PIDS": "56", + "OSD_POS_XY_PIDS": "57", + "OSD_POS_Z_PIDS": "58", + "OSD_VEL_XY_PIDS": "59", + "OSD_VEL_Z_PIDS": "60", + "OSD_HEADING_P": "61", + "OSD_BOARD_ALIGN_ROLL": "62", + "OSD_BOARD_ALIGN_PITCH": "63", + "OSD_RC_EXPO": "64", + "OSD_RC_YAW_EXPO": "65", + "OSD_THROTTLE_EXPO": "66", + "OSD_PITCH_RATE": "67", + "OSD_ROLL_RATE": "68", + "OSD_YAW_RATE": "69", + "OSD_MANUAL_RC_EXPO": "70", + "OSD_MANUAL_RC_YAW_EXPO": "71", + "OSD_MANUAL_PITCH_RATE": "72", + "OSD_MANUAL_ROLL_RATE": "73", + "OSD_MANUAL_YAW_RATE": "74", + "OSD_NAV_FW_CRUISE_THR": "75", + "OSD_NAV_FW_PITCH2THR": "76", + "OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "77", + "OSD_DEBUG": "78", + "OSD_FW_ALT_PID_OUTPUTS": "79", + "OSD_FW_POS_PID_OUTPUTS": "80", + "OSD_MC_VEL_X_PID_OUTPUTS": "81", + "OSD_MC_VEL_Y_PID_OUTPUTS": "82", + "OSD_MC_VEL_Z_PID_OUTPUTS": "83", + "OSD_MC_POS_XYZ_P_OUTPUTS": "84", + "OSD_3D_SPEED": "85", + "OSD_IMU_TEMPERATURE": "86", + "OSD_BARO_TEMPERATURE": "87", + "OSD_TEMP_SENSOR_0_TEMPERATURE": "88", + "OSD_TEMP_SENSOR_1_TEMPERATURE": "89", + "OSD_TEMP_SENSOR_2_TEMPERATURE": "90", + "OSD_TEMP_SENSOR_3_TEMPERATURE": "91", + "OSD_TEMP_SENSOR_4_TEMPERATURE": "92", + "OSD_TEMP_SENSOR_5_TEMPERATURE": "93", + "OSD_TEMP_SENSOR_6_TEMPERATURE": "94", + "OSD_TEMP_SENSOR_7_TEMPERATURE": "95", + "OSD_ALTITUDE_MSL": "96", + "OSD_PLUS_CODE": "97", + "OSD_MAP_SCALE": "98", + "OSD_MAP_REFERENCE": "99", + "OSD_GFORCE": "100", + "OSD_GFORCE_X": "101", + "OSD_GFORCE_Y": "102", + "OSD_GFORCE_Z": "103", + "OSD_RC_SOURCE": "104", + "OSD_VTX_POWER": "105", + "OSD_ESC_RPM": "106", + "OSD_ESC_TEMPERATURE": "107", + "OSD_AZIMUTH": "108", + "OSD_RSSI_DBM": "109", + "OSD_LQ_UPLINK": "110", + "OSD_SNR_DB": "111", + "OSD_TX_POWER_UPLINK": "112", + "OSD_GVAR_0": "113", + "OSD_GVAR_1": "114", + "OSD_GVAR_2": "115", + "OSD_GVAR_3": "116", + "OSD_TPA": "117", + "OSD_NAV_FW_CONTROL_SMOOTHNESS": "118", + "OSD_VERSION": "119", + "OSD_RANGEFINDER": "120", + "OSD_PLIMIT_REMAINING_BURST_TIME": "121", + "OSD_PLIMIT_ACTIVE_CURRENT_LIMIT": "122", + "OSD_PLIMIT_ACTIVE_POWER_LIMIT": "123", + "OSD_GLIDESLOPE": "124", + "OSD_GPS_MAX_SPEED": "125", + "OSD_3D_MAX_SPEED": "126", + "OSD_AIR_MAX_SPEED": "127", + "OSD_ACTIVE_PROFILE": "128", + "OSD_MISSION": "129", + "OSD_SWITCH_INDICATOR_0": "130", + "OSD_SWITCH_INDICATOR_1": "131", + "OSD_SWITCH_INDICATOR_2": "132", + "OSD_SWITCH_INDICATOR_3": "133", + "OSD_TPA_TIME_CONSTANT": "134", + "OSD_FW_LEVEL_TRIM": "135", + "OSD_GLIDE_TIME_REMAINING": "136", + "OSD_GLIDE_RANGE": "137", + "OSD_CLIMB_EFFICIENCY": "138", + "OSD_NAV_WP_MULTI_MISSION_INDEX": "139", + "OSD_GROUND_COURSE": "140", + "OSD_CROSS_TRACK_ERROR": "141", + "OSD_PILOT_NAME": "142", + "OSD_PAN_SERVO_CENTRED": "143", + "OSD_MULTI_FUNCTION": "144", + "OSD_ODOMETER": "145", + "OSD_PILOT_LOGO": "146", + "OSD_CUSTOM_ELEMENT_1": "147", + "OSD_CUSTOM_ELEMENT_2": "148", + "OSD_CUSTOM_ELEMENT_3": "149", + "OSD_ADSB_WARNING": "150", + "OSD_ADSB_INFO": "151", + "OSD_BLACKBOX": "152", + "OSD_FORMATION_FLIGHT": "153", + "OSD_CUSTOM_ELEMENT_4": "154", + "OSD_CUSTOM_ELEMENT_5": "155", + "OSD_CUSTOM_ELEMENT_6": "156", + "OSD_CUSTOM_ELEMENT_7": "157", + "OSD_CUSTOM_ELEMENT_8": "158", + "OSD_LQ_DOWNLINK": "159", + "OSD_RX_POWER_DOWNLINK": "160", + "OSD_RX_BAND": "161", + "OSD_RX_MODE": "162", + "OSD_COURSE_TO_FENCE": "163", + "OSD_H_DIST_TO_FENCE": "164", + "OSD_V_DIST_TO_FENCE": "165", + "OSD_NAV_FW_ALT_CONTROL_RESPONSE": "166", + "OSD_NAV_MIN_GROUND_SPEED": "167", + "OSD_THROTTLE_GAUGE": "168", + "OSD_ITEM_COUNT": "169" + }, + "osd_sidebar_arrow_e": { + "_source": "inav/src/main/io/osd_grid.c", + "OSD_SIDEBAR_ARROW_NONE": "0", + "OSD_SIDEBAR_ARROW_UP": "1", + "OSD_SIDEBAR_ARROW_DOWN": "2" + }, + "osd_sidebar_scroll_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_SIDEBAR_SCROLL_NONE": "0", + "OSD_SIDEBAR_SCROLL_ALTITUDE": "1", + "OSD_SIDEBAR_SCROLL_SPEED": "2", + "OSD_SIDEBAR_SCROLL_HOME_DISTANCE": "3", + "OSD_SIDEBAR_SCROLL_MAX": "OSD_SIDEBAR_SCROLL_HOME_DISTANCE" + }, + "osd_SpeedTypes_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_SPEED_TYPE_GROUND": "0", + "OSD_SPEED_TYPE_AIR": "1", + "OSD_SPEED_TYPE_3D": "2", + "OSD_SPEED_TYPE_MIN_GROUND": "3" + }, + "osd_stats_energy_unit_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_STATS_ENERGY_UNIT_MAH": "0", + "OSD_STATS_ENERGY_UNIT_WH": "1" + }, + "osd_unit_e": { + "_source": "inav/src/main/io/osd.h", + "OSD_UNIT_IMPERIAL": "0", + "OSD_UNIT_METRIC": "1", + "OSD_UNIT_METRIC_MPH": "2", + "OSD_UNIT_UK": "3", + "OSD_UNIT_GA": "4", + "OSD_UNIT_MAX": "OSD_UNIT_GA" + }, + "osdCustomElementType_e": { + "_source": "inav/src/main/io/osd/custom_elements.h", + "CUSTOM_ELEMENT_TYPE_NONE": "0", + "CUSTOM_ELEMENT_TYPE_TEXT": "1", + "CUSTOM_ELEMENT_TYPE_ICON_STATIC": "2", + "CUSTOM_ELEMENT_TYPE_ICON_GV": "3", + "CUSTOM_ELEMENT_TYPE_ICON_LC": "4", + "CUSTOM_ELEMENT_TYPE_GV_1": "5", + "CUSTOM_ELEMENT_TYPE_GV_2": "6", + "CUSTOM_ELEMENT_TYPE_GV_3": "7", + "CUSTOM_ELEMENT_TYPE_GV_4": "8", + "CUSTOM_ELEMENT_TYPE_GV_5": "9", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_1": "10", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_2": "11", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_1": "12", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_2": "13", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_1": "14", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_2": "15", + "CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_1": "16", + "CUSTOM_ELEMENT_TYPE_LC_1": "17", + "CUSTOM_ELEMENT_TYPE_LC_2": "18", + "CUSTOM_ELEMENT_TYPE_LC_3": "19", + "CUSTOM_ELEMENT_TYPE_LC_4": "20", + "CUSTOM_ELEMENT_TYPE_LC_5": "21", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_1": "22", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_2": "23", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_1": "24", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_2": "25", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_1": "26", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_2": "27", + "CUSTOM_ELEMENT_TYPE_LC_FLOAT_4_1": "28", + "CUSTOM_ELEMENT_TYPE_END": "29" + }, + "osdCustomElementTypeVisibility_e": { + "_source": "inav/src/main/io/osd/custom_elements.h", + "CUSTOM_ELEMENT_VISIBILITY_ALWAYS": "0", + "CUSTOM_ELEMENT_VISIBILITY_GV": "1", + "CUSTOM_ELEMENT_VISIBILITY_LOGIC_CON": "2" + }, + "osdDrawPointType_e": { + "_source": "inav/src/main/io/osd_common.h", + "OSD_DRAW_POINT_TYPE_GRID": "0", + "OSD_DRAW_POINT_TYPE_PIXEL": "1" + }, + "osdDriver_e": { + "_source": "inav/src/main/drivers/osd.h", + "OSD_DRIVER_NONE": "0", + "OSD_DRIVER_MAX7456": "1" + }, + "osdSpeedSource_e": { + "_source": "inav/src/main/io/osd_common.h", + "OSD_SPEED_SOURCE_GROUND": "0", + "OSD_SPEED_SOURCE_3D": "1", + "OSD_SPEED_SOURCE_AIR": "2" + }, + "outputMode_e": { + "_source": "inav/src/main/flight/mixer.h", + "OUTPUT_MODE_AUTO": "0", + "OUTPUT_MODE_MOTORS": "1", + "OUTPUT_MODE_SERVOS": "2", + "OUTPUT_MODE_LED": "3" + }, + "pageId_e": { + "_source": "inav/src/main/io/dashboard.h", + "PAGE_WELCOME": "0", + "PAGE_ARMED": "1", + "PAGE_STATUS": "2" + }, + "persistentObjectId_e": { + "_source": "inav/src/main/drivers/persistent.h", + "PERSISTENT_OBJECT_MAGIC": "0", + "PERSISTENT_OBJECT_RESET_REASON": "1", + "PERSISTENT_OBJECT_COUNT": "2" + }, + "pidAutotuneState_e": { + "_source": "inav/src/main/flight/pid_autotune.c", + "DEMAND_TOO_LOW": "0", + "DEMAND_UNDERSHOOT": "1", + "DEMAND_OVERSHOOT": "2", + "TUNE_UPDATED": "3" + }, + "pidControllerFlags_e": { + "_source": "inav/src/main/common/fp_pid.h", + "PID_DTERM_FROM_ERROR": "1 << 0", + "PID_ZERO_INTEGRATOR": "1 << 1", + "PID_SHRINK_INTEGRATOR": "1 << 2", + "PID_LIMIT_INTEGRATOR": "1 << 3", + "PID_FREEZE_INTEGRATOR": "1 << 4" + }, + "pidIndex_e": { + "_source": "inav/src/main/flight/pid.h", + "PID_ROLL": "0", + "PID_PITCH": "1", + "PID_YAW": "2", + "PID_POS_Z": "3", + "PID_POS_XY": "4", + "PID_VEL_XY": "5", + "PID_SURFACE": "6", + "PID_LEVEL": "7", + "PID_HEADING": "8", + "PID_VEL_Z": "9", + "PID_POS_HEADING": "10", + "PID_ITEM_COUNT": "11" + }, + "pidType_e": { + "_source": "inav/src/main/flight/pid.h", + "PID_TYPE_NONE": "0", + "PID_TYPE_PID": "1", + "PID_TYPE_PIFF": "2", + "PID_TYPE_AUTO": "3" + }, + "pinLabel_e": { + "_source": "inav/src/main/drivers/pwm_mapping.h", + "PIN_LABEL_NONE": "0", + "PIN_LABEL_LED": "1" + }, + "pitotSensor_e": { + "_source": "inav/src/main/sensors/pitotmeter.h", + "PITOT_NONE": "0", + "PITOT_AUTODETECT": "1", + "PITOT_MS4525": "2", + "PITOT_ADC": "3", + "PITOT_VIRTUAL": "4", + "PITOT_FAKE": "5", + "PITOT_MSP": "6", + "PITOT_DLVR": "7" + }, + "pollType_e": { + "_source": "inav/src/main/io/smartport_master.c", + "PT_ACTIVE_ID": "0", + "PT_INACTIVE_ID": "1" + }, + "portMode_t": { + "_source": "inav/src/main/drivers/serial.h", + "MODE_RX": "1 << 0", + "MODE_TX": "1 << 1", + "MODE_RXTX": "MODE_RX | MODE_TX" + }, + "portOptions_t": { + "_source": "inav/src/main/drivers/serial.h", + "SERIAL_NOT_INVERTED": "0 << 0", + "SERIAL_INVERTED": "1 << 0", + "SERIAL_STOPBITS_1": "0 << 1", + "SERIAL_STOPBITS_2": "1 << 1", + "SERIAL_PARITY_NO": "0 << 2", + "SERIAL_PARITY_EVEN": "1 << 2", + "SERIAL_UNIDIR": "0 << 3", + "SERIAL_BIDIR": "1 << 3", + "SERIAL_BIDIR_OD": "0 << 4", + "SERIAL_BIDIR_PP": "1 << 4", + "SERIAL_BIDIR_NOPULL": "1 << 5", + "SERIAL_BIDIR_UP": "0 << 5", + "SERIAL_LONGSTOP": "0 << 6", + "SERIAL_SHORTSTOP": "1 << 6" + }, + "portSharing_e": { + "_source": "inav/src/main/io/serial.h", + "PORTSHARING_UNUSED": "0", + "PORTSHARING_NOT_SHARED": "1", + "PORTSHARING_SHARED": "2" + }, + "pwmInitError_e": { + "_source": "inav/src/main/drivers/pwm_mapping.h", + "PWM_INIT_ERROR_NONE": "0", + "PWM_INIT_ERROR_TOO_MANY_MOTORS": "1", + "PWM_INIT_ERROR_TOO_MANY_SERVOS": "2", + "PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS": "3", + "PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS": "4", + "PWM_INIT_ERROR_TIMER_INIT_FAILED": "5" + }, + "quadrant_e": { + "_source": "inav/src/main/io/ledstrip.c", + "QUADRANT_NORTH": "1 << 0", + "QUADRANT_SOUTH": "1 << 1", + "QUADRANT_EAST": "1 << 2", + "QUADRANT_WEST": "1 << 3", + "QUADRANT_NORTH_EAST": "1 << 4", + "QUADRANT_SOUTH_EAST": "1 << 5", + "QUADRANT_NORTH_WEST": "1 << 6", + "QUADRANT_SOUTH_WEST": "1 << 7", + "QUADRANT_NONE": "1 << 8", + "QUADRANT_NOTDIAG": "1 << 9", + "QUADRANT_ANY": "QUADRANT_NORTH | QUADRANT_SOUTH | QUADRANT_EAST | QUADRANT_WEST | QUADRANT_NONE" + }, + "QUADSPIClockDivider_e": { + "_source": "inav/src/main/drivers/bus_quadspi.h", + "QUADSPI_CLOCK_INITIALISATION": "255", + "QUADSPI_CLOCK_SLOW": "19", + "QUADSPI_CLOCK_STANDARD": "9", + "QUADSPI_CLOCK_FAST": "3", + "QUADSPI_CLOCK_ULTRAFAST": "1" + }, + "QUADSPIDevice": { + "_source": "inav/src/main/drivers/bus_quadspi.h", + "QUADSPIINVALID": "-1", + "QUADSPIDEV_1": "0" + }, + "quadSpiMode_e": { + "_source": "inav/src/main/drivers/bus_quadspi.h", + "QUADSPI_MODE_BK1_ONLY": "0", + "QUADSPI_MODE_BK2_ONLY": "1", + "QUADSPI_MODE_DUAL_FLASH": "2" + }, + "rangefinderType_e": { + "_source": "inav/src/main/sensors/rangefinder.h", + "RANGEFINDER_NONE": "0", + "RANGEFINDER_SRF10": "1", + "RANGEFINDER_VL53L0X": "2", + "RANGEFINDER_MSP": "3", + "RANGEFINDER_BENEWAKE": "4", + "RANGEFINDER_VL53L1X": "5", + "RANGEFINDER_US42": "6", + "RANGEFINDER_TOF10102I2C": "7", + "RANGEFINDER_FAKE": "8", + "RANGEFINDER_TERARANGER_EVO": "9", + "RANGEFINDER_USD1_V0": "10", + "RANGEFINDER_NANORADAR": "11" + }, + "rc_alias_e": { + "_source": "inav/src/main/fc/rc_controls.h", + "ROLL": "0", + "PITCH": "1", + "YAW": "2", + "THROTTLE": "3", + "AUX1": "4", + "AUX2": "5", + "AUX3": "6", + "AUX4": "7", + "AUX5": "8", + "AUX6": "9", + "AUX7": "10", + "AUX8": "11", + "AUX9": "12", + "AUX10": "13", + "AUX11": "14", + "AUX12": "15", + "AUX13": "16", + "AUX14": "17", + "AUX15": [ + "(18)", + "USE_34CHANNELS" + ], + "AUX16": [ + "(19)", + "USE_34CHANNELS" + ], + "AUX17": [ + "(20)", + "USE_34CHANNELS" + ], + "AUX18": [ + "(21)", + "USE_34CHANNELS" + ], + "AUX19": [ + "(22)", + "USE_34CHANNELS" + ], + "AUX20": [ + "(23)", + "USE_34CHANNELS" + ], + "AUX21": [ + "(24)", + "USE_34CHANNELS" + ], + "AUX22": [ + "(25)", + "USE_34CHANNELS" + ], + "AUX23": [ + "(26)", + "USE_34CHANNELS" + ], + "AUX24": [ + "(27)", + "USE_34CHANNELS" + ], + "AUX25": [ + "(28)", + "USE_34CHANNELS" + ], + "AUX26": [ + "(29)", + "USE_34CHANNELS" + ], + "AUX27": [ + "(30)", + "USE_34CHANNELS" + ], + "AUX28": [ + "(31)", + "USE_34CHANNELS" + ], + "AUX29": [ + "(32)", + "USE_34CHANNELS" + ], + "AUX30": [ + "(33)", + "USE_34CHANNELS" + ] + }, + "RCDEVICE_5key_connection_event_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN": "1", + "RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE": "2" + }, + "rcdevice_5key_simulation_operation_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE": "0", + "RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET": "1", + "RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT": "2", + "RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT": "3", + "RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP": "4", + "RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN": "5" + }, + "rcdevice_camera_control_opeation_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN": "0", + "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN": "1", + "RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE": "2", + "RCDEVICE_PROTOCOL_CAM_CTRL_START_RECORDING": "3", + "RCDEVICE_PROTOCOL_CAM_CTRL_STOP_RECORDING": "4", + "RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION": "255" + }, + "rcdevice_features_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON": "(1 << 0)", + "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON": "(1 << 1)", + "RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE": "(1 << 2)", + "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE": "(1 << 3)", + "RCDEVICE_PROTOCOL_FEATURE_START_RECORDING": "(1 << 6)", + "RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING": "(1 << 7)", + "RCDEVICE_PROTOCOL_FEATURE_CMS_MENU": "(1 << 8)" + }, + "rcdevice_protocol_version_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_PROTOCOL_RCSPLIT_VERSION": "0", + "RCDEVICE_PROTOCOL_VERSION_1_0": "1", + "RCDEVICE_PROTOCOL_UNKNOWN": "2" + }, + "rcdeviceCamSimulationKeyEvent_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_CAM_KEY_NONE": "0", + "RCDEVICE_CAM_KEY_ENTER": "1", + "RCDEVICE_CAM_KEY_LEFT": "2", + "RCDEVICE_CAM_KEY_UP": "3", + "RCDEVICE_CAM_KEY_RIGHT": "4", + "RCDEVICE_CAM_KEY_DOWN": "5", + "RCDEVICE_CAM_KEY_CONNECTION_CLOSE": "6", + "RCDEVICE_CAM_KEY_CONNECTION_OPEN": "7", + "RCDEVICE_CAM_KEY_RELEASE": "8" + }, + "rcdeviceResponseStatus_e": { + "_source": "inav/src/main/io/rcdevice.h", + "RCDEVICE_RESP_SUCCESS": "0", + "RCDEVICE_RESP_INCORRECT_CRC": "1", + "RCDEVICE_RESP_TIMEOUT": "2" + }, + "resolutionType_e": { + "_source": "inav/src/main/io/displayport_msp_osd.c", + "SD_3016": "0", + "HD_5018": "1", + "HD_3016": "2", + "HD_6022": "3", + "HD_5320": "4" + }, + "resourceOwner_e": { + "_source": "inav/src/main/drivers/resource.h", + "OWNER_FREE": "0", + "OWNER_PWMIO": "1", + "OWNER_MOTOR": "2", + "OWNER_SERVO": "3", + "OWNER_SOFTSERIAL": "4", + "OWNER_ADC": "5", + "OWNER_SERIAL": "6", + "OWNER_TIMER": "7", + "OWNER_RANGEFINDER": "8", + "OWNER_SYSTEM": "9", + "OWNER_SPI": "10", + "OWNER_QUADSPI": "11", + "OWNER_I2C": "12", + "OWNER_SDCARD": "13", + "OWNER_FLASH": "14", + "OWNER_USB": "15", + "OWNER_BEEPER": "16", + "OWNER_OSD": "17", + "OWNER_BARO": "18", + "OWNER_MPU": "19", + "OWNER_INVERTER": "20", + "OWNER_LED_STRIP": "21", + "OWNER_LED": "22", + "OWNER_RX": "23", + "OWNER_TX": "24", + "OWNER_VTX": "25", + "OWNER_SPI_PREINIT": "26", + "OWNER_COMPASS": "27", + "OWNER_TEMPERATURE": "28", + "OWNER_1WIRE": "29", + "OWNER_AIRSPEED": "30", + "OWNER_OLED_DISPLAY": "31", + "OWNER_PINIO": "32", + "OWNER_IRLOCK": "33", + "OWNER_TOTAL_COUNT": "34" + }, + "resourceType_e": { + "_source": "inav/src/main/drivers/resource.h", + "RESOURCE_NONE": "0", + "RESOURCE_INPUT": "1", + "RESOURCE_TIMER": "2", + "RESOURCE_UART_TX": "3", + "RESOURCE_EXTI": "4", + "RESOURCE_I2C_SCL": "5", + "RESOURCE_SPI_SCK": "6", + "RESOURCE_QUADSPI_CLK": "7", + "RESOURCE_QUADSPI_BK1IO2": "8", + "RESOURCE_QUADSPI_BK2IO0": "9", + "RESOURCE_QUADSPI_BK2IO3": "10", + "RESOURCE_ADC_CH1": "11", + "RESOURCE_RX_CE": "12", + "RESOURCE_TOTAL_COUNT": "13" + }, + "reversibleMotorsThrottleState_e": { + "_source": "inav/src/main/flight/mixer.h", + "MOTOR_DIRECTION_FORWARD": "0", + "MOTOR_DIRECTION_BACKWARD": "1", + "MOTOR_DIRECTION_DEADBAND": "2" + }, + "rollPitchStatus_e": { + "_source": "inav/src/main/fc/rc_controls.h", + "NOT_CENTERED": "0", + "CENTERED": "1" + }, + "rssiSource_e": { + "_source": "inav/src/main/rx/rx.h", + "RSSI_SOURCE_NONE": "0", + "RSSI_SOURCE_AUTO": "1", + "RSSI_SOURCE_ADC": "2", + "RSSI_SOURCE_RX_CHANNEL": "3", + "RSSI_SOURCE_RX_PROTOCOL": "4", + "RSSI_SOURCE_MSP": "5" + }, + "rthState_e": { + "_source": "inav/src/main/flight/failsafe.h", + "RTH_IDLE": "0", + "RTH_IN_PROGRESS": "1", + "RTH_HAS_LANDED": "2" + }, + "rthTargetMode_e": { + "_source": "inav/src/main/navigation/navigation_private.h", + "RTH_HOME_ENROUTE_INITIAL": "0", + "RTH_HOME_ENROUTE_PROPORTIONAL": "1", + "RTH_HOME_ENROUTE_FINAL": "2", + "RTH_HOME_FINAL_LOITER": "3", + "RTH_HOME_FINAL_LAND": "4" + }, + "rthTrackbackMode_e": { + "_source": "inav/src/main/navigation/navigation.h", + "RTH_TRACKBACK_OFF": "0", + "RTH_TRACKBACK_ON": "1", + "RTH_TRACKBACK_FS": "2" + }, + "rxFrameState_e": { + "_source": "inav/src/main/rx/rx.h", + "RX_FRAME_PENDING": "0", + "RX_FRAME_COMPLETE": "(1 << 0)", + "RX_FRAME_FAILSAFE": "(1 << 1)", + "RX_FRAME_PROCESSING_REQUIRED": "(1 << 2)", + "RX_FRAME_DROPPED": "(1 << 3)" + }, + "rxReceiverType_e": { + "_source": "inav/src/main/rx/rx.h", + "RX_TYPE_NONE": "0", + "RX_TYPE_SERIAL": "1", + "RX_TYPE_MSP": "2", + "RX_TYPE_SIM": "3" + }, + "rxSerialReceiverType_e": { + "_source": "inav/src/main/rx/rx.h", + "SERIALRX_SPEKTRUM1024": "0", + "SERIALRX_SPEKTRUM2048": "1", + "SERIALRX_SBUS": "2", + "SERIALRX_SUMD": "3", + "SERIALRX_IBUS": "4", + "SERIALRX_JETIEXBUS": "5", + "SERIALRX_CRSF": "6", + "SERIALRX_FPORT": "7", + "SERIALRX_SBUS_FAST": "8", + "SERIALRX_FPORT2": "9", + "SERIALRX_SRXL2": "10", + "SERIALRX_GHST": "11", + "SERIALRX_MAVLINK": "12", + "SERIALRX_FBUS": "13", + "SERIALRX_SBUS2": "14" + }, + "safehomeUsageMode_e": { + "_source": "inav/src/main/navigation/navigation.h", + "SAFEHOME_USAGE_OFF": "0", + "SAFEHOME_USAGE_RTH": "1", + "SAFEHOME_USAGE_RTH_FS": "2" + }, + "sbasMode_e": { + "_source": "inav/src/main/io/gps.h", + "SBAS_AUTO": "0", + "SBAS_EGNOS": "1", + "SBAS_WAAS": "2", + "SBAS_MSAS": "3", + "SBAS_GAGAN": "4", + "SBAS_SPAN": "5", + "SBAS_NONE": "6" + }, + "sbusDecoderState_e": { + "_source": "inav/src/main/rx/sbus.c", + "STATE_SBUS_SYNC": "0", + "STATE_SBUS_PAYLOAD": "1", + "STATE_SBUS26_PAYLOAD": "2", + "STATE_SBUS_WAIT_SYNC": "3" + }, + "sdcardBlockOperation_e": { + "_source": "inav/src/main/drivers/sdcard/sdcard.h", + "SDCARD_BLOCK_OPERATION_READ": "0", + "SDCARD_BLOCK_OPERATION_WRITE": "1", + "SDCARD_BLOCK_OPERATION_ERASE": "2" + }, + "sdcardOperationStatus_e": { + "_source": "inav/src/main/drivers/sdcard/sdcard.h", + "SDCARD_OPERATION_IN_PROGRESS": "0", + "SDCARD_OPERATION_BUSY": "1", + "SDCARD_OPERATION_SUCCESS": "2", + "SDCARD_OPERATION_FAILURE": "3" + }, + "sdcardReceiveBlockStatus_e": { + "_source": "inav/src/main/drivers/sdcard/sdcard_spi.c", + "SDCARD_RECEIVE_SUCCESS": "0", + "SDCARD_RECEIVE_BLOCK_IN_PROGRESS": "1", + "SDCARD_RECEIVE_ERROR": "2" + }, + "sdcardState_e": { + "_source": "inav/src/main/drivers/sdcard/sdcard_impl.h", + "SDCARD_STATE_NOT_PRESENT": "0", + "SDCARD_STATE_RESET": "1", + "SDCARD_STATE_CARD_INIT_IN_PROGRESS": "2", + "SDCARD_STATE_INITIALIZATION_RECEIVE_CID": "3", + "SDCARD_STATE_READY": "4", + "SDCARD_STATE_READING": "5", + "SDCARD_STATE_SENDING_WRITE": "6", + "SDCARD_STATE_WAITING_FOR_WRITE": "7", + "SDCARD_STATE_WRITING_MULTIPLE_BLOCKS": "8", + "SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE": "9" + }, + "SDIODevice": { + "_source": "inav/src/main/drivers/sdio.h", + "SDIOINVALID": "-1", + "SDIODEV_1": "0", + "SDIODEV_2": "1" + }, + "sensor_align_e": { + "_source": "inav/src/main/drivers/sensor.h", + "ALIGN_DEFAULT": "0", + "CW0_DEG": "1", + "CW90_DEG": "2", + "CW180_DEG": "3", + "CW270_DEG": "4", + "CW0_DEG_FLIP": "5", + "CW90_DEG_FLIP": "6", + "CW180_DEG_FLIP": "7", + "CW270_DEG_FLIP": "8" + }, + "sensorIndex_e": { + "_source": "inav/src/main/sensors/sensors.h", + "SENSOR_INDEX_GYRO": "0", + "SENSOR_INDEX_ACC": "1", + "SENSOR_INDEX_BARO": "2", + "SENSOR_INDEX_MAG": "3", + "SENSOR_INDEX_RANGEFINDER": "4", + "SENSOR_INDEX_PITOT": "5", + "SENSOR_INDEX_OPFLOW": "6", + "SENSOR_INDEX_COUNT": "7" + }, + "sensors_e": { + "_source": "inav/src/main/sensors/sensors.h", + "SENSOR_GYRO": "1 << 0", + "SENSOR_ACC": "1 << 1", + "SENSOR_BARO": "1 << 2", + "SENSOR_MAG": "1 << 3", + "SENSOR_RANGEFINDER": "1 << 4", + "SENSOR_PITOT": "1 << 5", + "SENSOR_OPFLOW": "1 << 6", + "SENSOR_GPS": "1 << 7", + "SENSOR_GPSMAG": "1 << 8", + "SENSOR_TEMP": "1 << 9" + }, + "sensorTempCalState_e": { + "_source": "inav/src/main/sensors/sensors.h", + "SENSOR_TEMP_CAL_INITIALISE": "0", + "SENSOR_TEMP_CAL_IN_PROGRESS": "1", + "SENSOR_TEMP_CAL_COMPLETE": "2" + }, + "serialPortFunction_e": { + "_source": "inav/src/main/io/serial.h", + "FUNCTION_NONE": "0", + "FUNCTION_MSP": "(1 << 0)", + "FUNCTION_GPS": "(1 << 1)", + "FUNCTION_UNUSED_3": "(1 << 2)", + "FUNCTION_TELEMETRY_HOTT": "(1 << 3)", + "FUNCTION_TELEMETRY_LTM": "(1 << 4)", + "FUNCTION_TELEMETRY_SMARTPORT": "(1 << 5)", + "FUNCTION_RX_SERIAL": "(1 << 6)", + "FUNCTION_BLACKBOX": "(1 << 7)", + "FUNCTION_TELEMETRY_MAVLINK": "(1 << 8)", + "FUNCTION_TELEMETRY_IBUS": "(1 << 9)", + "FUNCTION_RCDEVICE": "(1 << 10)", + "FUNCTION_VTX_SMARTAUDIO": "(1 << 11)", + "FUNCTION_VTX_TRAMP": "(1 << 12)", + "FUNCTION_UNUSED_1": "(1 << 13)", + "FUNCTION_OPTICAL_FLOW": "(1 << 14)", + "FUNCTION_LOG": "(1 << 15)", + "FUNCTION_RANGEFINDER": "(1 << 16)", + "FUNCTION_VTX_FFPV": "(1 << 17)", + "FUNCTION_ESCSERIAL": "(1 << 18)", + "FUNCTION_TELEMETRY_SIM": "(1 << 19)", + "FUNCTION_FRSKY_OSD": "(1 << 20)", + "FUNCTION_DJI_HD_OSD": "(1 << 21)", + "FUNCTION_SERVO_SERIAL": "(1 << 22)", + "FUNCTION_TELEMETRY_SMARTPORT_MASTER": "(1 << 23)", + "FUNCTION_UNUSED_2": "(1 << 24)", + "FUNCTION_MSP_OSD": "(1 << 25)", + "FUNCTION_GIMBAL": "(1 << 26)", + "FUNCTION_GIMBAL_HEADTRACKER": "(1 << 27)" + }, + "serialPortIdentifier_e": { + "_source": "inav/src/main/io/serial.h", + "SERIAL_PORT_NONE": "-1", + "SERIAL_PORT_USART1": "0", + "SERIAL_PORT_USART2": "1", + "SERIAL_PORT_USART3": "2", + "SERIAL_PORT_USART4": "3", + "SERIAL_PORT_USART5": "4", + "SERIAL_PORT_USART6": "5", + "SERIAL_PORT_USART7": "6", + "SERIAL_PORT_USART8": "7", + "SERIAL_PORT_USB_VCP": "20", + "SERIAL_PORT_SOFTSERIAL1": "30", + "SERIAL_PORT_SOFTSERIAL2": "31", + "SERIAL_PORT_IDENTIFIER_MAX": "SERIAL_PORT_SOFTSERIAL2" + }, + "servoAutotrimState_e": { + "_source": "inav/src/main/flight/servos.c", + "AUTOTRIM_IDLE": "0", + "AUTOTRIM_COLLECTING": "1", + "AUTOTRIM_SAVE_PENDING": "2", + "AUTOTRIM_DONE": "3" + }, + "servoIndex_e": { + "_source": "inav/src/main/flight/servos.h", + "SERVO_GIMBAL_PITCH": "0", + "SERVO_GIMBAL_ROLL": "1", + "SERVO_ELEVATOR": "2", + "SERVO_FLAPPERON_1": "3", + "SERVO_FLAPPERON_2": "4", + "SERVO_RUDDER": "5", + "SERVO_BICOPTER_LEFT": "4", + "SERVO_BICOPTER_RIGHT": "5", + "SERVO_DUALCOPTER_LEFT": "4", + "SERVO_DUALCOPTER_RIGHT": "5", + "SERVO_SINGLECOPTER_1": "3", + "SERVO_SINGLECOPTER_2": "4", + "SERVO_SINGLECOPTER_3": "5", + "SERVO_SINGLECOPTER_4": "6" + }, + "servoProtocolType_e": { + "_source": "inav/src/main/drivers/pwm_mapping.h", + "SERVO_TYPE_PWM": "0", + "SERVO_TYPE_SBUS": "1", + "SERVO_TYPE_SBUS_PWM": "2" + }, + "setting_mode_e": { + "_source": "inav/src/main/fc/settings.h", + "MODE_DIRECT": "(0 << SETTING_MODE_OFFSET)", + "MODE_LOOKUP": "(1 << SETTING_MODE_OFFSET)" + }, + "setting_section_e": { + "_source": "inav/src/main/fc/settings.h", + "MASTER_VALUE": "(0 << SETTING_SECTION_OFFSET)", + "PROFILE_VALUE": "(1 << SETTING_SECTION_OFFSET)", + "CONTROL_VALUE": "(2 << SETTING_SECTION_OFFSET)", + "BATTERY_CONFIG_VALUE": "(3 << SETTING_SECTION_OFFSET)", + "MIXER_CONFIG_VALUE": "(4 << SETTING_SECTION_OFFSET)", + "EZ_TUNE_VALUE": "(5 << SETTING_SECTION_OFFSET)" + }, + "setting_type_e": { + "_source": "inav/src/main/fc/settings.h", + "VAR_UINT8": "(0 << SETTING_TYPE_OFFSET)", + "VAR_INT8": "(1 << SETTING_TYPE_OFFSET)", + "VAR_UINT16": "(2 << SETTING_TYPE_OFFSET)", + "VAR_INT16": "(3 << SETTING_TYPE_OFFSET)", + "VAR_UINT32": "(4 << SETTING_TYPE_OFFSET)", + "VAR_FLOAT": "(5 << SETTING_TYPE_OFFSET)", + "VAR_STRING": "(6 << SETTING_TYPE_OFFSET)" + }, + "simATCommandState_e": { + "_source": "inav/src/main/telemetry/sim.c", + "SIM_AT_OK": "0", + "SIM_AT_ERROR": "1", + "SIM_AT_WAITING_FOR_RESPONSE": "2" + }, + "simModuleState_e": { + "_source": "inav/src/main/telemetry/sim.c", + "SIM_MODULE_NOT_DETECTED": "0", + "SIM_MODULE_NOT_REGISTERED": "1", + "SIM_MODULE_REGISTERED": "2" + }, + "simReadState_e": { + "_source": "inav/src/main/telemetry/sim.c", + "SIM_READSTATE_RESPONSE": "0", + "SIM_READSTATE_SMS": "1", + "SIM_READSTATE_SKIP": "2" + }, + "simTelemetryState_e": { + "_source": "inav/src/main/telemetry/sim.c", + "SIM_STATE_INIT": "0", + "SIM_STATE_INIT2": "1", + "SIM_STATE_INIT_ENTER_PIN": "2", + "SIM_STATE_SET_MODES": "3", + "SIM_STATE_SEND_SMS": "4", + "SIM_STATE_SEND_SMS_ENTER_MESSAGE": "5" + }, + "simTransmissionState_e": { + "_source": "inav/src/main/telemetry/sim.c", + "SIM_TX_NO": "0", + "SIM_TX_FS": "1", + "SIM_TX": "2" + }, + "simTxFlags_e": { + "_source": "inav/src/main/telemetry/sim.h", + "SIM_TX_FLAG": "(1 << 0)", + "SIM_TX_FLAG_FAILSAFE": "(1 << 1)", + "SIM_TX_FLAG_GPS": "(1 << 2)", + "SIM_TX_FLAG_ACC": "(1 << 3)", + "SIM_TX_FLAG_LOW_ALT": "(1 << 4)", + "SIM_TX_FLAG_RESPONSE": "(1 << 5)" + }, + "simulatorFlags_t": { + "_source": "inav/src/main/fc/runtime_config.h", + "HITL_RESET_FLAGS": "(0 << 0)", + "HITL_ENABLE": "(1 << 0)", + "HITL_SIMULATE_BATTERY": "(1 << 1)", + "HITL_MUTE_BEEPER": "(1 << 2)", + "HITL_USE_IMU": "(1 << 3)", + "HITL_HAS_NEW_GPS_DATA": "(1 << 4)", + "HITL_EXT_BATTERY_VOLTAGE": "(1 << 5)", + "HITL_AIRSPEED": "(1 << 6)", + "HITL_EXTENDED_FLAGS": "(1 << 7)", + "HITL_GPS_TIMEOUT": "(1 << 8)", + "HITL_PITOT_FAILURE": "(1 << 9)" + }, + "smartAudioVersion_e": { + "_source": "inav/src/main/io/vtx_smartaudio.h", + "SA_UNKNOWN": "0", + "SA_1_0": "1", + "SA_2_0": "2", + "SA_2_1": "3" + }, + "smartportFuelUnit_e": { + "_source": "inav/src/main/telemetry/telemetry.h", + "SMARTPORT_FUEL_UNIT_PERCENT": "0", + "SMARTPORT_FUEL_UNIT_MAH": "1", + "SMARTPORT_FUEL_UNIT_MWH": "2" + }, + "softSerialPortIndex_e": { + "_source": "inav/src/main/drivers/serial_softserial.h", + "SOFTSERIAL1": "0", + "SOFTSERIAL2": "1" + }, + "SPIClockSpeed_e": { + "_source": "inav/src/main/drivers/bus_spi.h", + "SPI_CLOCK_INITIALIZATON": "0", + "SPI_CLOCK_SLOW": "1", + "SPI_CLOCK_STANDARD": "2", + "SPI_CLOCK_FAST": "3", + "SPI_CLOCK_ULTRAFAST": "4" + }, + "SPIDevice": { + "_source": "inav/src/main/drivers/bus_spi.h", + "SPIINVALID": "-1", + "SPIDEV_1": "0", + "SPIDEV_2": "1", + "SPIDEV_3": "2", + "SPIDEV_4": "3" + }, + "Srxl2BindRequest": { + "_source": "inav/src/main/rx/srxl2_types.h", + "EnterBindMode": "235", + "RequestBindStatus": "181", + "BoundDataReport": "219", + "SetBindInfo": "91" + }, + "Srxl2BindType": { + "_source": "inav/src/main/rx/srxl2_types.h", + "NotBound": "0", + "DSM2_1024_22ms": "1", + "DSM2_1024_MC24": "2", + "DMS2_2048_11ms": "18", + "DMSX_22ms": "162", + "DMSX_11ms": "178", + "Surface_DSM2_16_5ms": "99", + "DSMR_11ms_22ms": "226", + "DSMR_5_5ms": "228" + }, + "Srxl2ControlDataCommand": { + "_source": "inav/src/main/rx/srxl2_types.h", + "ChannelData": "0", + "FailsafeChannelData": "1", + "VTXData": "2" + }, + "Srxl2DeviceId": { + "_source": "inav/src/main/rx/srxl2_types.h", + "FlightControllerDefault": "48", + "FlightControllerMax": "63", + "Broadcast": "255" + }, + "Srxl2DeviceType": { + "_source": "inav/src/main/rx/srxl2_types.h", + "NoDevice": "0", + "RemoteReceiver": "1", + "Receiver": "2", + "FlightController": "3", + "ESC": "4", + "Reserved": "5", + "SRXLServo": "6", + "SRXLServo_2": "7", + "VTX": "8" + }, + "Srxl2PacketType": { + "_source": "inav/src/main/rx/srxl2_types.h", + "Handshake": "33", + "BindInfo": "65", + "ParameterConfiguration": "80", + "SignalQuality": "85", + "TelemetrySensorData": "128", + "ControlData": "205" + }, + "Srxl2State": { + "_source": "inav/src/main/rx/srxl2_types.h", + "Disabled": "0", + "ListenForActivity": "1", + "SendHandshake": "2", + "ListenForHandshake": "3", + "Running": "4" + }, + "stateFlags_t": { + "_source": "inav/src/main/fc/runtime_config.h", + "GPS_FIX_HOME": "(1 << 0)", + "GPS_FIX": "(1 << 1)", + "CALIBRATE_MAG": "(1 << 2)", + "SMALL_ANGLE": "(1 << 3)", + "FIXED_WING_LEGACY": "(1 << 4)", + "ANTI_WINDUP": "(1 << 5)", + "FLAPERON_AVAILABLE": "(1 << 6)", + "NAV_MOTOR_STOP_OR_IDLE": "(1 << 7)", + "COMPASS_CALIBRATED": "(1 << 8)", + "ACCELEROMETER_CALIBRATED": "(1 << 9)", + "GPS_ESTIMATED_FIX": [ + "(1 << 10)", + "USE_GPS_FIX_ESTIMATION" + ], + "NAV_CRUISE_BRAKING": "(1 << 11)", + "NAV_CRUISE_BRAKING_BOOST": "(1 << 12)", + "NAV_CRUISE_BRAKING_LOCKED": "(1 << 13)", + "NAV_EXTRA_ARMING_SAFETY_BYPASSED": "(1 << 14)", + "AIRMODE_ACTIVE": "(1 << 15)", + "ESC_SENSOR_ENABLED": "(1 << 16)", + "AIRPLANE": "(1 << 17)", + "MULTIROTOR": "(1 << 18)", + "ROVER": "(1 << 19)", + "BOAT": "(1 << 20)", + "ALTITUDE_CONTROL": "(1 << 21)", + "MOVE_FORWARD_ONLY": "(1 << 22)", + "SET_REVERSIBLE_MOTORS_FORWARD": "(1 << 23)", + "FW_HEADING_USE_YAW": "(1 << 24)", + "ANTI_WINDUP_DEACTIVATED": "(1 << 25)", + "LANDING_DETECTED": "(1 << 26)", + "IN_FLIGHT_EMERG_REARM": "(1 << 27)", + "TAILSITTER": "(1 << 28)" + }, + "stickPositions_e": { + "_source": "inav/src/main/fc/rc_controls.h", + "ROL_LO": "(1 << (2 * ROLL))", + "ROL_CE": "(3 << (2 * ROLL))", + "ROL_HI": "(2 << (2 * ROLL))", + "PIT_LO": "(1 << (2 * PITCH))", + "PIT_CE": "(3 << (2 * PITCH))", + "PIT_HI": "(2 << (2 * PITCH))", + "YAW_LO": "(1 << (2 * YAW))", + "YAW_CE": "(3 << (2 * YAW))", + "YAW_HI": "(2 << (2 * YAW))", + "THR_LO": "(1 << (2 * THROTTLE))", + "THR_CE": "(3 << (2 * THROTTLE))", + "THR_HI": "(2 << (2 * THROTTLE))" + }, + "systemState_e": { + "_source": "inav/src/main/fc/fc_init.h", + "SYSTEM_STATE_INITIALISING": "0", + "SYSTEM_STATE_CONFIG_LOADED": "(1 << 0)", + "SYSTEM_STATE_SENSORS_READY": "(1 << 1)", + "SYSTEM_STATE_MOTORS_READY": "(1 << 2)", + "SYSTEM_STATE_TRANSPONDER_ENABLED": "(1 << 3)", + "SYSTEM_STATE_READY": "(1 << 7)" + }, + "tchDmaState_e": { + "_source": "inav/src/main/drivers/timer.h", + "TCH_DMA_IDLE": "0", + "TCH_DMA_READY": "1", + "TCH_DMA_ACTIVE": "2" + }, + "tempSensorType_e": { + "_source": "inav/src/main/sensors/temperature.h", + "TEMP_SENSOR_NONE": "0", + "TEMP_SENSOR_LM75": "1", + "TEMP_SENSOR_DS18B20": "2" + }, + "throttleStatus_e": { + "_source": "inav/src/main/fc/rc_controls.h", + "THROTTLE_LOW": "0", + "THROTTLE_HIGH": "1" + }, + "throttleStatusType_e": { + "_source": "inav/src/main/fc/rc_controls.h", + "THROTTLE_STATUS_TYPE_RC": "0", + "THROTTLE_STATUS_TYPE_COMMAND": "1" + }, + "timerMode_e": { + "_source": "inav/src/main/drivers/serial_softserial.c", + "TIMER_MODE_SINGLE": "0", + "TIMER_MODE_DUAL": "1" + }, + "timerUsageFlag_e": { + "_source": "inav/src/main/drivers/timer.h", + "TIM_USE_ANY": "0", + "TIM_USE_PPM": "(1 << 0)", + "TIM_USE_PWM": "(1 << 1)", + "TIM_USE_MOTOR": "(1 << 2)", + "TIM_USE_SERVO": "(1 << 3)", + "TIM_USE_MC_CHNFW": "(1 << 4)", + "TIM_USE_LED": "(1 << 24)", + "TIM_USE_BEEPER": "(1 << 25)" + }, + "timId_e": { + "_source": "inav/src/main/io/ledstrip.c", + "timBlink": "0", + "timLarson": "1", + "timBattery": "2", + "timRssi": "3", + "timGps": [ + "(4)", + "USE_GPS" + ], + "timWarning": "5", + "timIndicator": "6", + "timAnimation": [ + "(7)", + "USE_LED_ANIMATION" + ], + "timRing": "8", + "timTimerCount": "9" + }, + "tristate_e": { + "_source": "inav/src/main/common/tristate.h", + "TRISTATE_AUTO": "0", + "TRISTATE_ON": "1", + "TRISTATE_OFF": "2" + }, + "tz_automatic_dst_e": { + "_source": "inav/src/main/common/time.h", + "TZ_AUTO_DST_OFF": "0", + "TZ_AUTO_DST_EU": "1", + "TZ_AUTO_DST_USA": "2" + }, + "UARTDevice_e": { + "_source": "inav/src/main/drivers/serial_uart.h", + "UARTDEV_1": "0", + "UARTDEV_2": "1", + "UARTDEV_3": "2", + "UARTDEV_4": "3", + "UARTDEV_5": "4", + "UARTDEV_6": "5", + "UARTDEV_7": "6", + "UARTDEV_8": "7", + "UARTDEV_MAX": "8" + }, + "uartInverterLine_e": { + "_source": "inav/src/main/drivers/uart_inverter.h", + "UART_INVERTER_LINE_NONE": "0", + "UART_INVERTER_LINE_RX": "1 << 0", + "UART_INVERTER_LINE_TX": "1 << 1" + }, + "ublox_nav_sig_health_e": { + "_source": "inav/src/main/io/gps_ublox.h", + "UBLOX_SIG_HEALTH_UNKNOWN": "0", + "UBLOX_SIG_HEALTH_HEALTHY": "1", + "UBLOX_SIG_HEALTH_UNHEALTHY": "2" + }, + "ublox_nav_sig_quality": { + "_source": "inav/src/main/io/gps_ublox.h", + "UBLOX_SIG_QUALITY_NOSIGNAL": "0", + "UBLOX_SIG_QUALITY_SEARCHING": "1", + "UBLOX_SIG_QUALITY_ACQUIRED": "2", + "UBLOX_SIG_QUALITY_UNUSABLE": "3", + "UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC": "4", + "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC": "5", + "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2": "6", + "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3": "7" + }, + "ubs_nav_fix_type_t": { + "_source": "inav/src/main/io/gps_ublox.h", + "FIX_NONE": "0", + "FIX_DEAD_RECKONING": "1", + "FIX_2D": "2", + "FIX_3D": "3", + "FIX_GPS_DEAD_RECKONING": "4", + "FIX_TIME": "5" + }, + "ubx_ack_state_t": { + "_source": "inav/src/main/io/gps_ublox.h", + "UBX_ACK_WAITING": "0", + "UBX_ACK_GOT_ACK": "1", + "UBX_ACK_GOT_NAK": "2" + }, + "ubx_nav_status_bits_t": { + "_source": "inav/src/main/io/gps_ublox.h", + "NAV_STATUS_FIX_VALID": "1" + }, + "ubx_protocol_bytes_t": { + "_source": "inav/src/main/io/gps_ublox.h", + "PREAMBLE1": "181", + "PREAMBLE2": "98", + "CLASS_NAV": "1", + "CLASS_ACK": "5", + "CLASS_CFG": "6", + "CLASS_MON": "10", + "MSG_CLASS_UBX": "1", + "MSG_CLASS_NMEA": "240", + "MSG_VER": "4", + "MSG_ACK_NACK": "0", + "MSG_ACK_ACK": "1", + "MSG_NMEA_GGA": "0", + "MSG_NMEA_GLL": "1", + "MSG_NMEA_GSA": "2", + "MSG_NMEA_GSV": "3", + "MSG_NMEA_RMC": "4", + "MSG_NMEA_VGS": "5", + "MSG_POSLLH": "2", + "MSG_STATUS": "3", + "MSG_SOL": "6", + "MSG_PVT": "7", + "MSG_VELNED": "18", + "MSG_TIMEUTC": "33", + "MSG_SVINFO": "48", + "MSG_NAV_SAT": "53", + "MSG_CFG_PRT": "0", + "MSG_CFG_RATE": "8", + "MSG_CFG_SET_RATE": "1", + "MSG_CFG_NAV_SETTINGS": "36", + "MSG_CFG_SBAS": "22", + "MSG_CFG_GNSS": "62", + "MSG_MON_GNSS": "40", + "MSG_NAV_SIG": "67" + }, + "vcselPeriodType_e": { + "_source": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c", + "VcselPeriodPreRange": "0", + "VcselPeriodFinalRange": "1" + }, + "videoSystem_e": { + "_source": "inav/src/main/drivers/osd.h", + "VIDEO_SYSTEM_AUTO": "0", + "VIDEO_SYSTEM_PAL": "1", + "VIDEO_SYSTEM_NTSC": "2", + "VIDEO_SYSTEM_HDZERO": "3", + "VIDEO_SYSTEM_DJIWTF": "4", + "VIDEO_SYSTEM_AVATAR": "5", + "VIDEO_SYSTEM_DJICOMPAT": "6", + "VIDEO_SYSTEM_DJICOMPAT_HD": "7", + "VIDEO_SYSTEM_DJI_NATIVE": "8" + }, + "voltageSensor_e": { + "_source": "inav/src/main/sensors/battery_config_structs.h", + "VOLTAGE_SENSOR_NONE": "0", + "VOLTAGE_SENSOR_ADC": "1", + "VOLTAGE_SENSOR_ESC": "2", + "VOLTAGE_SENSOR_FAKE": "3", + "VOLTAGE_SENSOR_SMARTPORT": "4", + "VOLTAGE_SENSOR_MAX": "VOLTAGE_SENSOR_SMARTPORT" + }, + "vs600Band_e": { + "_source": "inav/src/main/io/smartport_master.h", + "VS600_BAND_A": "0", + "VS600_BAND_B": "1", + "VS600_BAND_C": "2", + "VS600_BAND_D": "3", + "VS600_BAND_E": "4", + "VS600_BAND_F": "5" + }, + "vs600Power_e": { + "_source": "inav/src/main/io/smartport_master.h", + "VS600_POWER_PIT": "0", + "VS600_POWER_25MW": "1", + "VS600_POWER_200MW": "2", + "VS600_POWER_600MW": "3" + }, + "vtxDevType_e": { + "_source": "inav/src/main/drivers/vtx_common.h", + "VTXDEV_UNSUPPORTED": "0", + "VTXDEV_RTC6705": "1", + "VTXDEV_SMARTAUDIO": "3", + "VTXDEV_TRAMP": "4", + "VTXDEV_FFPV": "5", + "VTXDEV_MSP": "6", + "VTXDEV_UNKNOWN": "255" + }, + "vtxFrequencyGroups_e": { + "_source": "inav/src/main/drivers/vtx_common.h", + "FREQUENCYGROUP_5G8": "0", + "FREQUENCYGROUP_2G4": "1", + "FREQUENCYGROUP_1G3": "2" + }, + "vtxLowerPowerDisarm_e": { + "_source": "inav/src/main/io/vtx.h", + "VTX_LOW_POWER_DISARM_OFF": "0", + "VTX_LOW_POWER_DISARM_ALWAYS": "1", + "VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM": "2" + }, + "vtxProtoResponseType_e": { + "_source": "inav/src/main/io/vtx_tramp.c", + "VTX_RESPONSE_TYPE_NONE": "0", + "VTX_RESPONSE_TYPE_CAPABILITIES": "1", + "VTX_RESPONSE_TYPE_STATUS": "2" + }, + "vtxProtoState_e": { + "_source": "inav/src/main/io/vtx_tramp.c", + "VTX_STATE_RESET": "0", + "VTX_STATE_OFFILE": "1", + "VTX_STATE_DETECTING": "2", + "VTX_STATE_IDLE": "3", + "VTX_STATE_QUERY_DELAY": "4", + "VTX_STATE_QUERY_STATUS": "5", + "VTX_STATE_WAIT_STATUS": "6" + }, + "vtxScheduleParams_e": { + "_source": "inav/src/main/io/vtx.c", + "VTX_PARAM_POWER": "0", + "VTX_PARAM_BANDCHAN": "1", + "VTX_PARAM_PITMODE": "2", + "VTX_PARAM_COUNT": "3" + }, + "warningFlags_e": { + "_source": "inav/src/main/io/ledstrip.c", + "WARNING_ARMING_DISABLED": "0", + "WARNING_LOW_BATTERY": "1", + "WARNING_FAILSAFE": "2", + "WARNING_HW_ERROR": "3" + }, + "warningLedState_e": { + "_source": "inav/src/main/io/statusindicator.c", + "WARNING_LED_OFF": "0", + "WARNING_LED_ON": "1", + "WARNING_LED_FLASH": "2" + }, + "widgetAHIOptions_t": { + "_source": "inav/src/main/drivers/display_widgets.h", + "DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS": "1 << 0" + }, + "widgetAHIStyle_e": { + "_source": "inav/src/main/drivers/display_widgets.h", + "DISPLAY_WIDGET_AHI_STYLE_STAIRCASE": "0", + "DISPLAY_WIDGET_AHI_STYLE_LINE": "1" + }, + "wpFwTurnSmoothing_e": { + "_source": "inav/src/main/navigation/navigation.h", + "WP_TURN_SMOOTHING_OFF": "0", + "WP_TURN_SMOOTHING_ON": "1", + "WP_TURN_SMOOTHING_CUT": "2" + }, + "wpMissionPlannerStatus_e": { + "_source": "inav/src/main/navigation/navigation.h", + "WP_PLAN_WAIT": "0", + "WP_PLAN_SAVE": "1", + "WP_PLAN_OK": "2", + "WP_PLAN_FULL": "3" + }, + "zeroCalibrationState_e": { + "_source": "inav/src/main/common/calibration.h", + "ZERO_CALIBRATION_NONE": "0", + "ZERO_CALIBRATION_IN_PROGRESS": "1", + "ZERO_CALIBRATION_DONE": "2", + "ZERO_CALIBRATION_FAIL": "3" + } } } \ No newline at end of file diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md index 864efcd8a7e..9f1d8a1a28e 100644 --- a/docs/development/msp/inav_enums_ref.md +++ b/docs/development/msp/inav_enums_ref.md @@ -1756,7 +1756,7 @@ | `FEATURE_PWM_OUTPUT_ENABLE` | 1 << 28 | | | `FEATURE_OSD` | 1 << 29 | | | `FEATURE_FW_LAUNCH` | 1 << 30 | | -| `FEATURE_FW_AUTOTRIM` | 1 << 31 | | +| `FEATURE_FW_AUTOTRIM` | 1U << 31 | | --- ## `filterType_e` diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum deleted file mode 100644 index ff3e21a1d69..00000000000 --- a/docs/development/msp/msp_messages.checksum +++ /dev/null @@ -1 +0,0 @@ -82a3d2eee9d0d1fe609363a08405ed21 diff --git a/docs/development/msp/msp_messages.json b/docs/development/msp/msp_messages.json index e4c2a39993f..81875f05af7 100644 --- a/docs/development/msp/msp_messages.json +++ b/docs/development/msp/msp_messages.json @@ -1,10929 +1,10936 @@ { - "MSP_API_VERSION": { - "code": 1, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "mspProtocolVersion", - "ctype": "uint8_t", - "desc": "MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0)", - "units": "" - }, - { - "name": "apiVersionMajor", - "ctype": "uint8_t", - "desc": "INAV API Major version (`API_VERSION_MAJOR`)", - "units": "" - }, - { - "name": "apiVersionMinor", - "ctype": "uint8_t", - "desc": "INAV API Minor version (`API_VERSION_MINOR`)", - "units": "" - } - ] - }, - "notes": "Used by configurators to check compatibility.", - "description": "Provides the MSP protocol version and the INAV API version." - }, - "MSP_FC_VARIANT": { - "code": 2, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "fcVariantIdentifier", - "desc": "4-character identifier string (e.g., \"INAV\"). Defined by `flightControllerIdentifier`.", - "ctype": "char", - "array": true, - "array_size": 4, - "units": "" - } - ] + "version": { + "major": 2, + "minor": 0, + "patch": 0 + }, + "messages": { + "MSP_API_VERSION": { + "code": 1, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "mspProtocolVersion", + "ctype": "uint8_t", + "desc": "MSP Protocol version (`MSP_PROTOCOL_VERSION`, typically 0)", + "units": "" + }, + { + "name": "apiVersionMajor", + "ctype": "uint8_t", + "desc": "INAV API Major version (`API_VERSION_MAJOR`)", + "units": "" + }, + { + "name": "apiVersionMinor", + "ctype": "uint8_t", + "desc": "INAV API Minor version (`API_VERSION_MINOR`)", + "units": "" + } + ] + }, + "notes": "Used by configurators to check compatibility.", + "description": "Provides the MSP protocol version and the INAV API version." + }, + "MSP_FC_VARIANT": { + "code": 2, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "fcVariantIdentifier", + "desc": "4-character identifier string (e.g., \"INAV\"). Defined by `flightControllerIdentifier`.", + "ctype": "char", + "array": true, + "array_size": 4, + "units": "" + } + ] + }, + "notes": "See `FLIGHT_CONTROLLER_IDENTIFIER_LENGTH`.", + "description": "Identifies the flight controller firmware variant (e.g., INAV, Betaflight)." + }, + "MSP_FC_VERSION": { + "code": 3, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "fcVersionMajor", + "ctype": "uint8_t", + "desc": "Firmware Major version (`FC_VERSION_MAJOR`)", + "units": "" + }, + { + "name": "fcVersionMinor", + "ctype": "uint8_t", + "desc": "Firmware Minor version (`FC_VERSION_MINOR`)", + "units": "" + }, + { + "name": "fcVersionPatch", + "ctype": "uint8_t", + "desc": "Firmware Patch level (`FC_VERSION_PATCH_LEVEL`)", + "units": "" + } + ] + }, + "notes": "", + "description": "Provides the specific version number of the flight controller firmware." + }, + "MSP_BOARD_INFO": { + "code": 4, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "boardIdentifier", + "desc": "4-character UPPER CASE board identifier (`TARGET_BOARD_IDENTIFIER`)", + "ctype": "char", + "array": true, + "array_size": 4, + "units": "" + }, + { + "name": "hardwareRevision", + "ctype": "uint16_t", + "desc": "Hardware revision number. 0 if not detected (`USE_HARDWARE_REVISION_DETECTION`)", + "units": "" + }, + { + "name": "osdSupport", + "ctype": "uint8_t", + "desc": "OSD chip type: 0=None, 2=Onboard (`USE_OSD`). INAV does not support slave OSD (1)", + "units": "" + }, + { + "name": "commCapabilities", + "ctype": "uint8_t", + "desc": "Bitmask: Communication capabilities: Bit 0=VCP support (`USE_VCP`), Bit 1=SoftSerial support (`USE_SOFTSERIAL1`/`2`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "targetNameLength", + "ctype": "uint8_t", + "desc": "Length of the target name string that follows", + "units": "" + }, + { + "name": "targetName", + "desc": "Target name string (e.g., \"MATEKF405\"). Length given by previous field", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "`BOARD_IDENTIFIER_LENGTH` is 4.", + "description": "Provides information about the specific hardware board and its capabilities." + }, + "MSP_BUILD_INFO": { + "code": 5, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "buildDate", + "desc": "Build date string (e.g., \"Dec 31 2023\"). `BUILD_DATE_LENGTH`.", + "ctype": "char", + "array": true, + "array_size": 11, + "array_size_define": "BUILD_DATE_LENGTH", + "units": "" + }, + { + "name": "buildTime", + "desc": "Build time string (e.g., \"23:59:59\"). `BUILD_TIME_LENGTH`.", + "ctype": "char", + "array": true, + "array_size": 8, + "array_size_define": "BUILD_TIME_LENGTH", + "units": "" + }, + { + "name": "gitRevision", + "desc": "Short Git revision string. `GIT_SHORT_REVISION_LENGTH`.", + "ctype": "char", + "array": true, + "array_size": 8, + "array_size_define": "GIT_SHORT_REVISION_LENGTH", + "units": "" + } + ] + }, + "notes": "", + "description": "Provides build date, time, and Git revision of the firmware." + }, + "MSP_INAV_PID": { + "code": 6, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "legacyAsyncProcessing", + "ctype": "uint8_t", + "desc": "Legacy, unused. Always 0", + "value": 0 + }, + { + "name": "legacyAsyncValue1", + "ctype": "uint16_t", + "desc": "Legacy, unused. Always 0", + "value": 0 + }, + { + "name": "legacyAsyncValue2", + "ctype": "int16_t", + "desc": "Legacy, unused. Always 0", + "value": 0 + }, + { + "name": "headingHoldRateLimit", + "ctype": "uint8_t", + "desc": "Max rate for heading hold P term (`pidProfile()->heading_hold_rate_limit`)", + "units": "deg/s" + }, + { + "name": "headingHoldLpfFreq", + "ctype": "uint8_t", + "desc": "Fixed LPF frequency for heading hold error (`HEADING_HOLD_ERROR_LPF_FREQ`)", + "units": "Hz" + }, + { + "name": "legacyYawJumpLimit", + "ctype": "int16_t", + "desc": "Legacy, unused. Always 0", + "value": 0 + }, + { + "name": "legacyGyroLpf", + "ctype": "uint8_t", + "desc": "Fixed value `GYRO_LPF_256HZ`", + "units": "Hz" + }, + { + "name": "accLpfHz", + "ctype": "uint8_t", + "desc": "Accelerometer LPF frequency (`accelerometerConfig()->acc_lpf_hz`) cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz", + "units": "Hz" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Reserved. Always 0", + "value": 0 + }, + { + "name": "reserved2", + "ctype": "uint8_t", + "desc": "Reserved. Always 0", + "value": 0 + }, + { + "name": "reserved3", + "ctype": "uint8_t", + "desc": "Reserved. Always 0", + "value": 0 + }, + { + "name": "reserved4", + "ctype": "uint8_t", + "desc": "Reserved. Always 0", + "value": 0 + } + ] + }, + "notes": "Superseded by `MSP2_PID` for core PIDs and other specific messages for filter settings.", + "description": "Retrieves legacy INAV-specific PID controller related settings. Many fields are now obsolete or placeholders." }, - "notes": "See `FLIGHT_CONTROLLER_IDENTIFIER_LENGTH`.", - "description": "Identifies the flight controller firmware variant (e.g., INAV, Betaflight)." - }, - "MSP_FC_VERSION": { - "code": 3, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "fcVersionMajor", - "ctype": "uint8_t", - "desc": "Firmware Major version (`FC_VERSION_MAJOR`)", - "units": "" - }, - { - "name": "fcVersionMinor", - "ctype": "uint8_t", - "desc": "Firmware Minor version (`FC_VERSION_MINOR`)", - "units": "" - }, - { - "name": "fcVersionPatch", - "ctype": "uint8_t", - "desc": "Firmware Patch level (`FC_VERSION_PATCH_LEVEL`)", - "units": "" - } - ] + "MSP_SET_INAV_PID": { + "code": 7, + "mspv": 1, + "request": { + "payload": [ + { + "name": "legacyAsyncProcessing", + "ctype": "uint8_t", + "desc": "Legacy, ignored" + }, + { + "name": "legacyAsyncValue1", + "ctype": "int16_t", + "desc": "Legacy, ignored" + }, + { + "name": "legacyAsyncValue2", + "ctype": "int16_t", + "desc": "Legacy, ignored" + }, + { + "name": "headingHoldRateLimit", + "ctype": "uint8_t", + "desc": "Sets `pidProfileMutable()->heading_hold_rate_limit`.", + "units": "deg/s" + }, + { + "name": "headingHoldLpfFreq", + "ctype": "uint8_t", + "desc": "Ignored (fixed value `HEADING_HOLD_ERROR_LPF_FREQ` used)", + "units": "Hz" + }, + { + "name": "legacyYawJumpLimit", + "ctype": "int16_t", + "desc": "Legacy, ignored" + }, + { + "name": "legacyGyroLpf", + "ctype": "uint8_t", + "desc": "Ignored (historically mapped to `gyro_lpf_e` values).", + "units": "" + }, + { + "name": "accLpfHz", + "ctype": "uint8_t", + "desc": "Sets `accelerometerConfigMutable()->acc_lpf_hz`.", + "units": "Hz" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "reserved2", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "reserved3", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "reserved4", + "ctype": "uint8_t", + "desc": "Ignored" + } + ] + }, + "reply": null, + "notes": "Expects 15 bytes.", + "description": "Sets legacy INAV-specific PID controller related settings." + }, + "MSP_NAME": { + "code": 10, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "craftName", + "desc": "The craft name string (`systemConfig()->craftName`). Null termination is *not* explicitly sent, the length is determined by the payload size", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "", + "description": "Returns the user-defined craft name." }, - "notes": "", - "description": "Provides the specific version number of the flight controller firmware." - }, - "MSP_BOARD_INFO": { - "code": 4, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "boardIdentifier", - "desc": "4-character UPPER CASE board identifier (`TARGET_BOARD_IDENTIFIER`)", - "ctype": "char", - "array": true, - "array_size": 4, - "units": "" - }, - { - "name": "hardwareRevision", - "ctype": "uint16_t", - "desc": "Hardware revision number. 0 if not detected (`USE_HARDWARE_REVISION_DETECTION`)", - "units": "" - }, - { - "name": "osdSupport", - "ctype": "uint8_t", - "desc": "OSD chip type: 0=None, 2=Onboard (`USE_OSD`). INAV does not support slave OSD (1)", - "units": "" - }, - { - "name": "commCapabilities", - "ctype": "uint8_t", - "desc": "Bitmask: Communication capabilities: Bit 0=VCP support (`USE_VCP`), Bit 1=SoftSerial support (`USE_SOFTSERIAL1`/`2`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "targetNameLength", - "ctype": "uint8_t", - "desc": "Length of the target name string that follows", - "units": "" - }, - { - "name": "targetName", - "desc": "Target name string (e.g., \"MATEKF405\"). Length given by previous field", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] + "MSP_SET_NAME": { + "code": 11, + "mspv": 1, + "request": { + "payload": [ + { + "name": "craftName", + "desc": "The new craft name string. Automatically null-terminated by the FC", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "reply": null, + "variable_len": true, + "notes": "Maximum length is `MAX_NAME_LENGTH`.", + "description": "Sets the user-defined craft name." + }, + "MSP_NAV_POSHOLD": { + "code": 12, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "userControlMode", + "ctype": "uint8_t", + "desc": "Navigation user control mode NAV_GPS_ATTI (0) or NAV_GPS_CRUISE (1)" + }, + { + "name": "maxAutoSpeed", + "ctype": "uint16_t", + "desc": "Max speed in autonomous modes (`navConfig()->general.max_auto_speed`)", + "units": "cm/s" + }, + { + "name": "maxAutoClimbRate", + "ctype": "uint16_t", + "desc": "Max climb rate in autonomous modes (uses `fw.max_auto_climb_rate` or `mc.max_auto_climb_rate` based on platform)", + "units": "cm/s" + }, + { + "name": "maxManualSpeed", + "ctype": "uint16_t", + "desc": "Max speed in manual modes with GPS aiding (`navConfig()->general.max_manual_speed`)", + "units": "cm/s" + }, + { + "name": "maxManualClimbRate", + "ctype": "uint16_t", + "desc": "Max climb rate in manual modes with GPS aiding (uses `fw.max_manual_climb_rate` or `mc.max_manual_climb_rate`)", + "units": "cm/s" + }, + { + "name": "mcMaxBankAngle", + "ctype": "uint8_t", + "desc": "Max bank angle for multirotor position hold (`navConfig()->mc.max_bank_angle`)", + "units": "degrees" + }, + { + "name": "mcAltHoldThrottleType", + "ctype": "uint8_t", + "desc": "Enum `navMcAltHoldThrottle_e` mirrored from `navConfig()->mc.althold_throttle_type`.", + "units": "Enum", + "enum": "navMcAltHoldThrottle_e" + }, + { + "name": "mcHoverThrottle", + "ctype": "uint16_t", + "desc": "Multirotor hover throttle PWM value (`currentBatteryProfile->nav.mc.hover_throttle`).", + "units": "PWM" + } + ] + }, + "notes": "", + "description": "Retrieves navigation position hold and general manual/auto flight parameters. Some parameters depend on the platform type (Multirotor vs Fixed Wing)." }, - "variable_len": true, - "notes": "`BOARD_IDENTIFIER_LENGTH` is 4.", - "description": "Provides information about the specific hardware board and its capabilities." - }, - "MSP_BUILD_INFO": { - "code": 5, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "buildDate", - "desc": "Build date string (e.g., \"Dec 31 2023\"). `BUILD_DATE_LENGTH`.", - "ctype": "char", - "array": true, - "array_size": 11, - "array_size_define": "BUILD_DATE_LENGTH", - "units": "" - }, - { - "name": "buildTime", - "desc": "Build time string (e.g., \"23:59:59\"). `BUILD_TIME_LENGTH`.", - "ctype": "char", - "array": true, - "array_size": 8, - "array_size_define": "BUILD_TIME_LENGTH", - "units": "" - }, - { - "name": "gitRevision", - "desc": "Short Git revision string. `GIT_SHORT_REVISION_LENGTH`.", - "ctype": "char", - "array": true, - "array_size": 8, - "array_size_define": "GIT_SHORT_REVISION_LENGTH", - "units": "" - } - ] + "MSP_SET_NAV_POSHOLD": { + "code": 13, + "mspv": 1, + "request": { + "payload": [ + { + "name": "userControlMode", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->general.flags.user_control_mode`. WARNING: uses unnamed enum in navigation.h 'NAV_GPS_ATTI/NAV_GPS_CRUISE'", + "units": "Enum", + "enum": "navUserControlMode_e" + }, + { + "name": "maxAutoSpeed", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.max_auto_speed`.", + "units": "cm/s" + }, + { + "name": "maxAutoClimbRate", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->fw.max_auto_climb_rate` or `navConfigMutable()->mc.max_auto_climb_rate` based on `mixerConfig()->platformType`.", + "units": "cm/s" + }, + { + "name": "maxManualSpeed", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.max_manual_speed`.", + "units": "cm/s" + }, + { + "name": "maxManualClimbRate", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->fw.max_manual_climb_rate` or `navConfigMutable()->mc.max_manual_climb_rate`.", + "units": "cm/s" + }, + { + "name": "mcMaxBankAngle", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->mc.max_bank_angle`.", + "units": "degrees" + }, + { + "name": "mcAltHoldThrottleType", + "ctype": "uint8_t", + "desc": "Enum `navMcAltHoldThrottle_e`; updates `navConfigMutable()->mc.althold_throttle_type`.", + "units": "Enum", + "enum": "navMcAltHoldThrottle_e" + }, + { + "name": "mcHoverThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->nav.mc.hover_throttle`.", + "units": "PWM" + } + ] + }, + "reply": null, + "notes": "Expects 13 bytes.", + "description": "Sets navigation position hold and general manual/auto flight parameters." + }, + "MSP_CALIBRATION_DATA": { + "code": 14, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "accCalibAxisFlags", + "ctype": "uint8_t", + "desc": "Bitmask: Flags indicating which axes of the accelerometer have been calibrated (`accGetCalibrationAxisFlags()`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "accZeroX", + "ctype": "int16_t", + "desc": "Accelerometer zero offset for X-axis (`accelerometerConfig()->accZero.raw[X]`)", + "units": "Raw ADC" + }, + { + "name": "accZeroY", + "ctype": "int16_t", + "desc": "Accelerometer zero offset for Y-axis (`accelerometerConfig()->accZero.raw[Y]`)", + "units": "Raw ADC" + }, + { + "name": "accZeroZ", + "ctype": "int16_t", + "desc": "Accelerometer zero offset for Z-axis (`accelerometerConfig()->accZero.raw[Z]`)", + "units": "Raw ADC" + }, + { + "name": "accGainX", + "ctype": "int16_t", + "desc": "Accelerometer gain/scale for X-axis (`accelerometerConfig()->accGain.raw[X]`)", + "units": "Raw ADC" + }, + { + "name": "accGainY", + "ctype": "int16_t", + "desc": "Accelerometer gain/scale for Y-axis (`accelerometerConfig()->accGain.raw[Y]`)", + "units": "Raw ADC" + }, + { + "name": "accGainZ", + "ctype": "int16_t", + "desc": "Accelerometer gain/scale for Z-axis (`accelerometerConfig()->accGain.raw[Z]`)", + "units": "Raw ADC" + }, + { + "name": "magZeroX", + "ctype": "int16_t", + "desc": "Magnetometer zero offset for X-axis (`compassConfig()->magZero.raw[X]`). 0 if `USE_MAG` disabled", + "units": "Raw ADC" + }, + { + "name": "magZeroY", + "ctype": "int16_t", + "desc": "Magnetometer zero offset for Y-axis (`compassConfig()->magZero.raw[Y]`). 0 if `USE_MAG` disabled", + "units": "Raw ADC" + }, + { + "name": "magZeroZ", + "ctype": "int16_t", + "desc": "Magnetometer zero offset for Z-axis (`compassConfig()->magZero.raw[Z]`). 0 if `USE_MAG` disabled", + "units": "Raw ADC" + }, + { + "name": "opflowScale", + "ctype": "uint16_t", + "desc": "Optical flow scale factor (`opticalFlowConfig()->opflow_scale * 256`). 0 if `USE_OPFLOW` disabled", + "units": "Scale * 256" + }, + { + "name": "magGainX", + "ctype": "int16_t", + "desc": "Magnetometer gain/scale for X-axis (`compassConfig()->magGain[X]`). 0 if `USE_MAG` disabled", + "units": "Raw ADC" + }, + { + "name": "magGainY", + "ctype": "int16_t", + "desc": "Magnetometer gain/scale for Y-axis (`compassConfig()->magGain[Y]`). 0 if `USE_MAG` disabled", + "units": "Raw ADC" + }, + { + "name": "magGainZ", + "ctype": "int16_t", + "desc": "Magnetometer gain/scale for Z-axis (`compassConfig()->magGain[Z]`). 0 if `USE_MAG` disabled", + "units": "Raw ADC" + } + ] + }, + "notes": "Total size 27 bytes. Fields related to optional sensors are zero if the sensor is not used.", + "description": "Retrieves sensor calibration data (Accelerometer zero/gain, Magnetometer zero/gain, Optical Flow scale)." }, - "notes": "", - "description": "Provides build date, time, and Git revision of the firmware." - }, - "MSP_INAV_PID": { - "code": 6, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "legacyAsyncProcessing", - "ctype": "uint8_t", - "desc": "Legacy, unused. Always 0", - "value": 0 - }, - { - "name": "legacyAsyncValue1", - "ctype": "uint16_t", - "desc": "Legacy, unused. Always 0", - "value": 0 - }, - { - "name": "legacyAsyncValue2", - "ctype": "int16_t", - "desc": "Legacy, unused. Always 0", - "value": 0 - }, - { - "name": "headingHoldRateLimit", - "ctype": "uint8_t", - "desc": "Max rate for heading hold P term (`pidProfile()->heading_hold_rate_limit`)", - "units": "deg/s" - }, - { - "name": "headingHoldLpfFreq", - "ctype": "uint8_t", - "desc": "Fixed LPF frequency for heading hold error (`HEADING_HOLD_ERROR_LPF_FREQ`)", - "units": "Hz" - }, - { - "name": "legacyYawJumpLimit", - "ctype": "int16_t", - "desc": "Legacy, unused. Always 0", - "value": 0 - }, - { - "name": "legacyGyroLpf", - "ctype": "uint8_t", - "desc": "Fixed value `GYRO_LPF_256HZ`", - "units": "Hz" - }, - { - "name": "accLpfHz", - "ctype": "uint8_t", - "desc": "Accelerometer LPF frequency (`accelerometerConfig()->acc_lpf_hz`) cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz", - "units": "Hz" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Reserved. Always 0", - "value": 0 - }, - { - "name": "reserved2", - "ctype": "uint8_t", - "desc": "Reserved. Always 0", - "value": 0 - }, - { - "name": "reserved3", - "ctype": "uint8_t", - "desc": "Reserved. Always 0", - "value": 0 - }, - { - "name": "reserved4", - "ctype": "uint8_t", - "desc": "Reserved. Always 0", - "value": 0 - } - ] + "MSP_SET_CALIBRATION_DATA": { + "code": 15, + "mspv": 1, + "request": { + "payload": [ + { + "name": "accZeroX", + "ctype": "int16_t", + "desc": "Sets `accelerometerConfigMutable()->accZero.raw[X]`.", + "units": "Raw ADC" + }, + { + "name": "accZeroY", + "ctype": "int16_t", + "desc": "Sets `accelerometerConfigMutable()->accZero.raw[Y]`.", + "units": "Raw ADC" + }, + { + "name": "accZeroZ", + "ctype": "int16_t", + "desc": "Sets `accelerometerConfigMutable()->accZero.raw[Z]`.", + "units": "Raw ADC" + }, + { + "name": "accGainX", + "ctype": "int16_t", + "desc": "Sets `accelerometerConfigMutable()->accGain.raw[X]`.", + "units": "Raw ADC" + }, + { + "name": "accGainY", + "ctype": "int16_t", + "desc": "Sets `accelerometerConfigMutable()->accGain.raw[Y]`.", + "units": "Raw ADC" + }, + { + "name": "accGainZ", + "ctype": "int16_t", + "desc": "Sets `accelerometerConfigMutable()->accGain.raw[Z]`.", + "units": "Raw ADC" + }, + { + "name": "magZeroX", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->magZero.raw[X]` (if `USE_MAG`)", + "units": "Raw ADC" + }, + { + "name": "magZeroY", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->magZero.raw[Y]` (if `USE_MAG`)", + "units": "Raw ADC" + }, + { + "name": "magZeroZ", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->magZero.raw[Z]` (if `USE_MAG`)", + "units": "Raw ADC" + }, + { + "name": "opflowScale", + "ctype": "uint16_t", + "desc": "Sets `opticalFlowConfigMutable()->opflow_scale = value / 256.0f` (if `USE_OPFLOW`)", + "units": "Scale * 256" + }, + { + "name": "magGainX", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->magGain[X]` (if `USE_MAG`)", + "units": "Raw ADC" + }, + { + "name": "magGainY", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->magGain[Y]` (if `USE_MAG`)", + "units": "Raw ADC" + }, + { + "name": "magGainZ", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->magGain[Z]` (if `USE_MAG`)", + "units": "Raw ADC" + } + ] + }, + "reply": null, + "notes": "Minimum payload 18 bytes. Adds +6 bytes for magnetometer zeros, +2 for optical flow scale, and +6 for magnetometer gains when those features (`USE_MAG`, `USE_OPFLOW`) are compiled in.", + "description": "Sets sensor calibration data." + }, + "MSP_POSITION_ESTIMATION_CONFIG": { + "code": 16, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "weightZBaroP", + "ctype": "uint16_t", + "desc": "Barometer Z position fusion weight (`positionEstimationConfig()->w_z_baro_p * 100`)", + "units": "Weight * 100" + }, + { + "name": "weightZGPSP", + "ctype": "uint16_t", + "desc": "GPS Z position fusion weight (`positionEstimationConfig()->w_z_gps_p * 100`)", + "units": "Weight * 100" + }, + { + "name": "weightZGPSV", + "ctype": "uint16_t", + "desc": "GPS Z velocity fusion weight (`positionEstimationConfig()->w_z_gps_v * 100`)", + "units": "Weight * 100" + }, + { + "name": "weightXYGPSP", + "ctype": "uint16_t", + "desc": "GPS XY position fusion weight (`positionEstimationConfig()->w_xy_gps_p * 100`)", + "units": "Weight * 100" + }, + { + "name": "weightXYGPSV", + "ctype": "uint16_t", + "desc": "GPS XY velocity fusion weight (`positionEstimationConfig()->w_xy_gps_v * 100`)", + "units": "Weight * 100" + }, + { + "name": "minSats", + "ctype": "uint8_t", + "desc": "Minimum satellites required for GPS use (`gpsConfigMutable()->gpsMinSats`)", + "units": "Count" + }, + { + "name": "useGPSVelNED", + "ctype": "uint8_t", + "desc": "Legacy flag, always 1 (GPS velocity is always used if available)", + "units": "Boolean", + "value": 1 + } + ] + }, + "notes": "", + "description": "Retrieves parameters related to the INAV position estimation fusion weights and GPS minimum satellite count." }, - "notes": "Superseded by `MSP2_PID` for core PIDs and other specific messages for filter settings.", - "description": "Retrieves legacy INAV-specific PID controller related settings. Many fields are now obsolete or placeholders." - }, - "MSP_SET_INAV_PID": { - "code": 7, - "mspv": 1, - "request": { - "payload": [ - { - "name": "legacyAsyncProcessing", - "ctype": "uint8_t", - "desc": "Legacy, ignored" - }, - { - "name": "legacyAsyncValue1", - "ctype": "int16_t", - "desc": "Legacy, ignored" - }, - { - "name": "legacyAsyncValue2", - "ctype": "int16_t", - "desc": "Legacy, ignored" - }, - { - "name": "headingHoldRateLimit", - "ctype": "uint8_t", - "desc": "Sets `pidProfileMutable()->heading_hold_rate_limit`.", - "units": "deg/s" - }, - { - "name": "headingHoldLpfFreq", - "ctype": "uint8_t", - "desc": "Ignored (fixed value `HEADING_HOLD_ERROR_LPF_FREQ` used)", - "units": "Hz" - }, - { - "name": "legacyYawJumpLimit", - "ctype": "int16_t", - "desc": "Legacy, ignored" - }, - { - "name": "legacyGyroLpf", - "ctype": "uint8_t", - "desc": "Ignored (historically mapped to `gyro_lpf_e` values).", - "units": "" - }, - { - "name": "accLpfHz", - "ctype": "uint8_t", - "desc": "Sets `accelerometerConfigMutable()->acc_lpf_hz`.", - "units": "Hz" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "reserved2", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "reserved3", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "reserved4", - "ctype": "uint8_t", - "desc": "Ignored" - } - ] + "MSP_SET_POSITION_ESTIMATION_CONFIG": { + "code": 17, + "mspv": 1, + "request": { + "payload": [ + { + "name": "weightZBaroP", + "ctype": "uint16_t", + "desc": "Sets `positionEstimationConfigMutable()->w_z_baro_p = value / 100.0f` (constrained 0.0-10.0)", + "units": "Weight * 100" + }, + { + "name": "weightZGPSP", + "ctype": "uint16_t", + "desc": "Sets `positionEstimationConfigMutable()->w_z_gps_p = value / 100.0f` (constrained 0.0-10.0)", + "units": "Weight * 100" + }, + { + "name": "weightZGPSV", + "ctype": "uint16_t", + "desc": "Sets `positionEstimationConfigMutable()->w_z_gps_v = value / 100.0f` (constrained 0.0-10.0)", + "units": "Weight * 100" + }, + { + "name": "weightXYGPSP", + "ctype": "uint16_t", + "desc": "Sets `positionEstimationConfigMutable()->w_xy_gps_p = value / 100.0f` (constrained 0.0-10.0)", + "units": "Weight * 100" + }, + { + "name": "weightXYGPSV", + "ctype": "uint16_t", + "desc": "Sets `positionEstimationConfigMutable()->w_xy_gps_v = value / 100.0f` (constrained 0.0-10.0)", + "units": "Weight * 100" + }, + { + "name": "minSats", + "ctype": "uint8_t", + "desc": "Sets `gpsConfigMutable()->gpsMinSats` (constrained 5-10)", + "units": "Count" + }, + { + "name": "useGPSVelNED", + "ctype": "uint8_t", + "desc": "Legacy flag, ignored", + "units": "Boolean" + } + ] + }, + "reply": null, + "notes": "Expects 12 bytes.", + "description": "Sets parameters related to the INAV position estimation fusion weights and GPS minimum satellite count." }, - "reply": null, - "notes": "Expects 15 bytes.", - "description": "Sets legacy INAV-specific PID controller related settings." - }, - "MSP_NAME": { - "code": 10, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "craftName", - "desc": "The craft name string (`systemConfig()->craftName`). Null termination is *not* explicitly sent, the length is determined by the payload size", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] + "MSP_WP_MISSION_LOAD": { + "code": 18, + "mspv": 1, + "request": { + "payload": [ + { + "name": "missionID", + "ctype": "uint8_t", + "desc": "Reserved for future use, currently ignored", + "units": "" + } + ] + }, + "reply": null, + "notes": "Only functional if `NAV_NON_VOLATILE_WAYPOINT_STORAGE` is defined. Requires 1 byte payload. Returns error if loading fails.", + "description": "Commands the FC to load the waypoint mission stored in non-volatile memory (e.g., EEPROM or FlashFS) into the active mission buffer." }, - "variable_len": true, - "notes": "", - "description": "Returns the user-defined craft name." - }, - "MSP_SET_NAME": { - "code": 11, - "mspv": 1, - "request": { - "payload": [ - { - "name": "craftName", - "desc": "The new craft name string. Automatically null-terminated by the FC", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] + "MSP_WP_MISSION_SAVE": { + "code": 19, + "mspv": 1, + "request": { + "payload": [ + { + "name": "missionID", + "ctype": "uint8_t", + "desc": "Reserved for future use, currently ignored", + "units": "" + } + ] + }, + "reply": null, + "notes": "Only functional if `NAV_NON_VOLATILE_WAYPOINT_STORAGE` is defined. Requires 1 byte payload. Returns error if saving fails.", + "description": "Commands the FC to save the currently active waypoint mission from RAM to non-volatile memory (e.g., EEPROM or FlashFS)." + }, + "MSP_WP_GETINFO": { + "code": 20, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "wpCapabilities", + "ctype": "uint8_t", + "desc": "Reserved for future waypoint capabilities flags. Currently always 0", + "units": "", + "value": 0 + }, + { + "name": "maxWaypoints", + "ctype": "uint8_t", + "desc": "Maximum number of waypoints supported (`NAV_MAX_WAYPOINTS`)", + "units": "" + }, + { + "name": "missionValid", + "ctype": "uint8_t", + "desc": "Boolean flag indicating if the current mission in RAM is valid (`isWaypointListValid()`)", + "units": "" + }, + { + "name": "waypointCount", + "ctype": "uint8_t", + "desc": "Number of waypoints currently defined in the mission (`getWaypointCount()`)", + "units": "" + } + ] + }, + "notes": "", + "description": "Retrieves information about the waypoint mission capabilities and the status of the currently loaded mission." + }, + "MSP_RTH_AND_LAND_CONFIG": { + "code": 21, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "minRthDistance", + "ctype": "uint16_t", + "desc": "Minimum distance from home required for RTH to engage (`navConfig()->general.min_rth_distance`)", + "units": "cm" + }, + { + "name": "rthClimbFirst", + "ctype": "uint8_t", + "desc": "Flag: Climb to RTH altitude before returning (`navConfig()->general.flags.rth_climb_first`)", + "units": "Boolean" + }, + { + "name": "rthClimbIgnoreEmerg", + "ctype": "uint8_t", + "desc": "Flag: Climb even in emergency RTH (`navConfig()->general.flags.rth_climb_ignore_emerg`)", + "units": "Boolean" + }, + { + "name": "rthTailFirst", + "ctype": "uint8_t", + "desc": "Flag: Return tail-first during RTH (`navConfig()->general.flags.rth_tail_first`)", + "units": "Boolean" + }, + { + "name": "rthAllowLanding", + "ctype": "uint8_t", + "desc": "Flag: Allow automatic landing after RTH (`navConfig()->general.flags.rth_allow_landing`)", + "units": "Boolean" + }, + { + "name": "rthAltControlMode", + "ctype": "uint8_t", + "desc": "RTH altitude control mode (`navConfig()->general.flags.rth_alt_control_mode`). WARNING: uses unnamed enum in navigation.h:253 'NAV_RTH_NO_ALT...'", + "units": "Enum", + "enum": "navRthAltControlMode_e" + }, + { + "name": "rthAbortThreshold", + "ctype": "uint16_t", + "desc": "Distance increase threshold to abort RTH (`navConfig()->general.rth_abort_threshold`)", + "units": "cm" + }, + { + "name": "rthAltitude", + "ctype": "uint16_t", + "desc": "Target RTH altitude (`navConfig()->general.rth_altitude`)", + "units": "cm" + }, + { + "name": "landMinAltVspd", + "ctype": "uint16_t", + "desc": "Landing vertical speed at minimum slowdown altitude (`navConfig()->general.land_minalt_vspd`)", + "units": "cm/s" + }, + { + "name": "landMaxAltVspd", + "ctype": "uint16_t", + "desc": "Landing vertical speed at maximum slowdown altitude (`navConfig()->general.land_maxalt_vspd`)", + "units": "cm/s" + }, + { + "name": "landSlowdownMinAlt", + "ctype": "uint16_t", + "desc": "Altitude below which `landMinAltVspd` applies (`navConfig()->general.land_slowdown_minalt`)", + "units": "cm" + }, + { + "name": "landSlowdownMaxAlt", + "ctype": "uint16_t", + "desc": "Altitude above which `landMaxAltVspd` applies (`navConfig()->general.land_slowdown_maxalt`)", + "units": "cm" + }, + { + "name": "emergDescentRate", + "ctype": "uint16_t", + "desc": "Vertical speed during emergency landing descent (`navConfig()->general.emerg_descent_rate`)", + "units": "cm/s" + } + ] + }, + "notes": "", + "description": "Retrieves configuration parameters related to Return-to-Home (RTH) and automatic landing behaviors." }, - "reply": null, - "variable_len": true, - "notes": "Maximum length is `MAX_NAME_LENGTH`.", - "description": "Sets the user-defined craft name." - }, - "MSP_NAV_POSHOLD": { - "code": 12, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "userControlMode", - "ctype": "uint8_t", - "desc": "Navigation user control mode NAV_GPS_ATTI (0) or NAV_GPS_CRUISE (1)" - }, - { - "name": "maxAutoSpeed", - "ctype": "uint16_t", - "desc": "Max speed in autonomous modes (`navConfig()->general.max_auto_speed`)", - "units": "cm/s" - }, - { - "name": "maxAutoClimbRate", - "ctype": "uint16_t", - "desc": "Max climb rate in autonomous modes (uses `fw.max_auto_climb_rate` or `mc.max_auto_climb_rate` based on platform)", - "units": "cm/s" - }, - { - "name": "maxManualSpeed", - "ctype": "uint16_t", - "desc": "Max speed in manual modes with GPS aiding (`navConfig()->general.max_manual_speed`)", - "units": "cm/s" - }, - { - "name": "maxManualClimbRate", - "ctype": "uint16_t", - "desc": "Max climb rate in manual modes with GPS aiding (uses `fw.max_manual_climb_rate` or `mc.max_manual_climb_rate`)", - "units": "cm/s" - }, - { - "name": "mcMaxBankAngle", - "ctype": "uint8_t", - "desc": "Max bank angle for multirotor position hold (`navConfig()->mc.max_bank_angle`)", - "units": "degrees" - }, - { - "name": "mcAltHoldThrottleType", - "ctype": "uint8_t", - "desc": "Enum `navMcAltHoldThrottle_e` mirrored from `navConfig()->mc.althold_throttle_type`.", - "units": "Enum", - "enum": "navMcAltHoldThrottle_e" - }, - { - "name": "mcHoverThrottle", - "ctype": "uint16_t", - "desc": "Multirotor hover throttle PWM value (`currentBatteryProfile->nav.mc.hover_throttle`).", - "units": "PWM" - } - ] + "MSP_SET_RTH_AND_LAND_CONFIG": { + "code": 22, + "mspv": 1, + "request": { + "payload": [ + { + "name": "minRthDistance", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.min_rth_distance`.", + "units": "cm" + }, + { + "name": "rthClimbFirst", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->general.flags.rth_climb_first`.", + "units": "Boolean" + }, + { + "name": "rthClimbIgnoreEmerg", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->general.flags.rth_climb_ignore_emerg`.", + "units": "Boolean" + }, + { + "name": "rthTailFirst", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->general.flags.rth_tail_first`.", + "units": "Boolean" + }, + { + "name": "rthAllowLanding", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->general.flags.rth_allow_landing`.", + "units": "Boolean" + }, + { + "name": "rthAltControlMode", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->general.flags.rth_alt_control_mode`. WARNING: uses unnamed enum in navigation.h:253", + "units": "Enum", + "enum": "navRthAltControlMode_e" + }, + { + "name": "rthAbortThreshold", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.rth_abort_threshold`.", + "units": "cm" + }, + { + "name": "rthAltitude", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.rth_altitude`.", + "units": "cm" + }, + { + "name": "landMinAltVspd", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.land_minalt_vspd`.", + "units": "cm/s" + }, + { + "name": "landMaxAltVspd", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.land_maxalt_vspd`.", + "units": "cm/s" + }, + { + "name": "landSlowdownMinAlt", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.land_slowdown_minalt`.", + "units": "cm" + }, + { + "name": "landSlowdownMaxAlt", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.land_slowdown_maxalt`.", + "units": "cm" + }, + { + "name": "emergDescentRate", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->general.emerg_descent_rate`.", + "units": "cm/s" + } + ] + }, + "reply": null, + "notes": "Expects 21 bytes.", + "description": "Sets configuration parameters related to Return-to-Home (RTH) and automatic landing behaviors." + }, + "MSP_FW_CONFIG": { + "code": 23, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "cruiseThrottle", + "ctype": "uint16_t", + "desc": "Cruise throttle command (`currentBatteryProfile->nav.fw.cruise_throttle`).", + "units": "PWM" + }, + { + "name": "minThrottle", + "ctype": "uint16_t", + "desc": "Minimum throttle during autonomous flight (`currentBatteryProfile->nav.fw.min_throttle`).", + "units": "PWM" + }, + { + "name": "maxThrottle", + "ctype": "uint16_t", + "desc": "Maximum throttle during autonomous flight (`currentBatteryProfile->nav.fw.max_throttle`).", + "units": "PWM" + }, + { + "name": "maxBankAngle", + "ctype": "uint8_t", + "desc": "Maximum bank angle allowed (`navConfig()->fw.max_bank_angle`)", + "units": "degrees" + }, + { + "name": "maxClimbAngle", + "ctype": "uint8_t", + "desc": "Maximum pitch angle during climb (`navConfig()->fw.max_climb_angle`)", + "units": "degrees" + }, + { + "name": "maxDiveAngle", + "ctype": "uint8_t", + "desc": "Maximum negative pitch angle during descent (`navConfig()->fw.max_dive_angle`)", + "units": "degrees" + }, + { + "name": "pitchToThrottle", + "ctype": "uint8_t", + "desc": "Pitch-to-throttle gain (`currentBatteryProfile->nav.fw.pitch_to_throttle`); PWM microseconds per degree (10 units β‰ˆ 1% throttle).", + "units": "us/deg" + }, + { + "name": "loiterRadius", + "ctype": "uint16_t", + "desc": "Default loiter radius (`navConfig()->fw.loiter_radius`).", + "units": "cm" + } + ] + }, + "notes": "", + "description": "Retrieves configuration parameters specific to Fixed Wing navigation." }, - "notes": "", - "description": "Retrieves navigation position hold and general manual/auto flight parameters. Some parameters depend on the platform type (Multirotor vs Fixed Wing)." - }, - "MSP_SET_NAV_POSHOLD": { - "code": 13, - "mspv": 1, - "request": { - "payload": [ - { - "name": "userControlMode", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->general.flags.user_control_mode`. WARNING: uses unnamed enum in navigation.h 'NAV_GPS_ATTI/NAV_GPS_CRUISE'", - "units": "Enum", - "enum": "navUserControlMode_e" - }, - { - "name": "maxAutoSpeed", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.max_auto_speed`.", - "units": "cm/s" - }, - { - "name": "maxAutoClimbRate", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->fw.max_auto_climb_rate` or `navConfigMutable()->mc.max_auto_climb_rate` based on `mixerConfig()->platformType`.", - "units": "cm/s" - }, - { - "name": "maxManualSpeed", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.max_manual_speed`.", - "units": "cm/s" - }, - { - "name": "maxManualClimbRate", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->fw.max_manual_climb_rate` or `navConfigMutable()->mc.max_manual_climb_rate`.", - "units": "cm/s" - }, - { - "name": "mcMaxBankAngle", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->mc.max_bank_angle`.", - "units": "degrees" - }, - { - "name": "mcAltHoldThrottleType", - "ctype": "uint8_t", - "desc": "Enum `navMcAltHoldThrottle_e`; updates `navConfigMutable()->mc.althold_throttle_type`.", - "units": "Enum", - "enum": "navMcAltHoldThrottle_e" - }, - { - "name": "mcHoverThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->nav.mc.hover_throttle`.", - "units": "PWM" - } - ] - }, - "reply": null, - "notes": "Expects 13 bytes.", - "description": "Sets navigation position hold and general manual/auto flight parameters." - }, - "MSP_CALIBRATION_DATA": { - "code": 14, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "accCalibAxisFlags", - "ctype": "uint8_t", - "desc": "Bitmask: Flags indicating which axes of the accelerometer have been calibrated (`accGetCalibrationAxisFlags()`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "accZeroX", - "ctype": "int16_t", - "desc": "Accelerometer zero offset for X-axis (`accelerometerConfig()->accZero.raw[X]`)", - "units": "Raw ADC" - }, - { - "name": "accZeroY", - "ctype": "int16_t", - "desc": "Accelerometer zero offset for Y-axis (`accelerometerConfig()->accZero.raw[Y]`)", - "units": "Raw ADC" - }, - { - "name": "accZeroZ", - "ctype": "int16_t", - "desc": "Accelerometer zero offset for Z-axis (`accelerometerConfig()->accZero.raw[Z]`)", - "units": "Raw ADC" - }, - { - "name": "accGainX", - "ctype": "int16_t", - "desc": "Accelerometer gain/scale for X-axis (`accelerometerConfig()->accGain.raw[X]`)", - "units": "Raw ADC" - }, - { - "name": "accGainY", - "ctype": "int16_t", - "desc": "Accelerometer gain/scale for Y-axis (`accelerometerConfig()->accGain.raw[Y]`)", - "units": "Raw ADC" - }, - { - "name": "accGainZ", - "ctype": "int16_t", - "desc": "Accelerometer gain/scale for Z-axis (`accelerometerConfig()->accGain.raw[Z]`)", - "units": "Raw ADC" - }, - { - "name": "magZeroX", - "ctype": "int16_t", - "desc": "Magnetometer zero offset for X-axis (`compassConfig()->magZero.raw[X]`). 0 if `USE_MAG` disabled", - "units": "Raw ADC" - }, - { - "name": "magZeroY", - "ctype": "int16_t", - "desc": "Magnetometer zero offset for Y-axis (`compassConfig()->magZero.raw[Y]`). 0 if `USE_MAG` disabled", - "units": "Raw ADC" - }, - { - "name": "magZeroZ", - "ctype": "int16_t", - "desc": "Magnetometer zero offset for Z-axis (`compassConfig()->magZero.raw[Z]`). 0 if `USE_MAG` disabled", - "units": "Raw ADC" - }, - { - "name": "opflowScale", - "ctype": "uint16_t", - "desc": "Optical flow scale factor (`opticalFlowConfig()->opflow_scale * 256`). 0 if `USE_OPFLOW` disabled", - "units": "Scale * 256" - }, - { - "name": "magGainX", - "ctype": "int16_t", - "desc": "Magnetometer gain/scale for X-axis (`compassConfig()->magGain[X]`). 0 if `USE_MAG` disabled", - "units": "Raw ADC" - }, - { - "name": "magGainY", - "ctype": "int16_t", - "desc": "Magnetometer gain/scale for Y-axis (`compassConfig()->magGain[Y]`). 0 if `USE_MAG` disabled", - "units": "Raw ADC" - }, - { - "name": "magGainZ", - "ctype": "int16_t", - "desc": "Magnetometer gain/scale for Z-axis (`compassConfig()->magGain[Z]`). 0 if `USE_MAG` disabled", - "units": "Raw ADC" - } - ] - }, - "notes": "Total size 27 bytes. Fields related to optional sensors are zero if the sensor is not used.", - "description": "Retrieves sensor calibration data (Accelerometer zero/gain, Magnetometer zero/gain, Optical Flow scale)." - }, - "MSP_SET_CALIBRATION_DATA": { - "code": 15, - "mspv": 1, - "request": { - "payload": [ - { - "name": "accZeroX", - "ctype": "int16_t", - "desc": "Sets `accelerometerConfigMutable()->accZero.raw[X]`.", - "units": "Raw ADC" - }, - { - "name": "accZeroY", - "ctype": "int16_t", - "desc": "Sets `accelerometerConfigMutable()->accZero.raw[Y]`.", - "units": "Raw ADC" - }, - { - "name": "accZeroZ", - "ctype": "int16_t", - "desc": "Sets `accelerometerConfigMutable()->accZero.raw[Z]`.", - "units": "Raw ADC" - }, - { - "name": "accGainX", - "ctype": "int16_t", - "desc": "Sets `accelerometerConfigMutable()->accGain.raw[X]`.", - "units": "Raw ADC" - }, - { - "name": "accGainY", - "ctype": "int16_t", - "desc": "Sets `accelerometerConfigMutable()->accGain.raw[Y]`.", - "units": "Raw ADC" - }, - { - "name": "accGainZ", - "ctype": "int16_t", - "desc": "Sets `accelerometerConfigMutable()->accGain.raw[Z]`.", - "units": "Raw ADC" - }, - { - "name": "magZeroX", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->magZero.raw[X]` (if `USE_MAG`)", - "units": "Raw ADC" - }, - { - "name": "magZeroY", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->magZero.raw[Y]` (if `USE_MAG`)", - "units": "Raw ADC" - }, - { - "name": "magZeroZ", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->magZero.raw[Z]` (if `USE_MAG`)", - "units": "Raw ADC" - }, - { - "name": "opflowScale", - "ctype": "uint16_t", - "desc": "Sets `opticalFlowConfigMutable()->opflow_scale = value / 256.0f` (if `USE_OPFLOW`)", - "units": "Scale * 256" - }, - { - "name": "magGainX", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->magGain[X]` (if `USE_MAG`)", - "units": "Raw ADC" - }, - { - "name": "magGainY", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->magGain[Y]` (if `USE_MAG`)", - "units": "Raw ADC" - }, - { - "name": "magGainZ", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->magGain[Z]` (if `USE_MAG`)", - "units": "Raw ADC" - } - ] + "MSP_SET_FW_CONFIG": { + "code": 24, + "mspv": 1, + "request": { + "payload": [ + { + "name": "cruiseThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->nav.fw.cruise_throttle`.", + "units": "PWM" + }, + { + "name": "minThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->nav.fw.min_throttle`.", + "units": "PWM" + }, + { + "name": "maxThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->nav.fw.max_throttle`.", + "units": "PWM" + }, + { + "name": "maxBankAngle", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->fw.max_bank_angle`.", + "units": "degrees" + }, + { + "name": "maxClimbAngle", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->fw.max_climb_angle`.", + "units": "degrees" + }, + { + "name": "maxDiveAngle", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->fw.max_dive_angle`.", + "units": "degrees" + }, + { + "name": "pitchToThrottle", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->nav.fw.pitch_to_throttle` (PWM microseconds per degree; 10 units β‰ˆ 1% throttle).", + "units": "us/deg" + }, + { + "name": "loiterRadius", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->fw.loiter_radius`.", + "units": "cm" + } + ] + }, + "reply": null, + "notes": "Expects 12 bytes.", + "description": "Sets configuration parameters specific to Fixed Wing navigation." + }, + "MSP_MODE_RANGES": { + "code": 34, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "modePermanentId", + "ctype": "uint8_t", + "desc": "Permanent ID of the flight mode (maps to `boxId` via `findBoxByActiveBoxId`). 0 if entry unused", + "units": "ID" + }, + { + "name": "auxChannelIndex", + "ctype": "uint8_t", + "desc": "0-based index of the AUX channel used for activation", + "units": "Index" + }, + { + "name": "rangeStartStep", + "ctype": "uint8_t", + "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", + "units": "step" + }, + { + "name": "rangeEndStep", + "ctype": "uint8_t", + "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", + "units": "step" + } + ], + "repeating": "MAX_MODE_ACTIVATION_CONDITION_COUNT" + }, + "notes": "The number of steps and mapping to PWM values depends on internal range calculations.", + "description": "Returns all defined mode activation ranges (aux channel assignments for flight modes)." }, - "reply": null, - "notes": "Minimum payload 18 bytes. Adds +6 bytes for magnetometer zeros, +2 for optical flow scale, and +6 for magnetometer gains when those features (`USE_MAG`, `USE_OPFLOW`) are compiled in.", - "description": "Sets sensor calibration data." - }, - "MSP_POSITION_ESTIMATION_CONFIG": { - "code": 16, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "weightZBaroP", - "ctype": "uint16_t", - "desc": "Barometer Z position fusion weight (`positionEstimationConfig()->w_z_baro_p * 100`)", - "units": "Weight * 100" - }, - { - "name": "weightZGPSP", - "ctype": "uint16_t", - "desc": "GPS Z position fusion weight (`positionEstimationConfig()->w_z_gps_p * 100`)", - "units": "Weight * 100" - }, - { - "name": "weightZGPSV", - "ctype": "uint16_t", - "desc": "GPS Z velocity fusion weight (`positionEstimationConfig()->w_z_gps_v * 100`)", - "units": "Weight * 100" - }, - { - "name": "weightXYGPSP", - "ctype": "uint16_t", - "desc": "GPS XY position fusion weight (`positionEstimationConfig()->w_xy_gps_p * 100`)", - "units": "Weight * 100" - }, - { - "name": "weightXYGPSV", - "ctype": "uint16_t", - "desc": "GPS XY velocity fusion weight (`positionEstimationConfig()->w_xy_gps_v * 100`)", - "units": "Weight * 100" - }, - { - "name": "minSats", - "ctype": "uint8_t", - "desc": "Minimum satellites required for GPS use (`gpsConfigMutable()->gpsMinSats`)", - "units": "Count" - }, - { - "name": "useGPSVelNED", - "ctype": "uint8_t", - "desc": "Legacy flag, always 1 (GPS velocity is always used if available)", - "units": "Boolean", - "value": 1 - } - ] + "MSP_SET_MODE_RANGE": { + "code": 35, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rangeIndex", + "ctype": "uint8_t", + "desc": "Index of the mode range to set (0 to `MAX_MODE_ACTIVATION_CONDITION_COUNT - 1`)", + "units": "Index" + }, + { + "name": "modePermanentId", + "ctype": "uint8_t", + "desc": "Permanent ID of the flight mode to assign", + "units": "ID" + }, + { + "name": "auxChannelIndex", + "ctype": "uint8_t", + "desc": "0-based index of the AUX channel", + "units": "Index" + }, + { + "name": "rangeStartStep", + "ctype": "uint8_t", + "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", + "units": "step" + }, + { + "name": "rangeEndStep", + "ctype": "uint8_t", + "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", + "units": "step" + } + ] + }, + "reply": null, + "notes": "Expects 5 bytes. Updates the mode configuration and recalculates used mode flags. Returns error if `rangeIndex` or `modePermanentId` is invalid.", + "description": "Sets a single mode activation range by its index." + }, + "MSP_FEATURE": { + "code": 36, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "featureMask", + "ctype": "uint32_t", + "desc": "Bitmask: active features (see `featureMask()`)", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "notes": "Feature bits are defined in `feature.h`.", + "description": "Returns a bitmask of enabled features." }, - "notes": "", - "description": "Retrieves parameters related to the INAV position estimation fusion weights and GPS minimum satellite count." - }, - "MSP_SET_POSITION_ESTIMATION_CONFIG": { - "code": 17, - "mspv": 1, - "request": { - "payload": [ - { - "name": "weightZBaroP", - "ctype": "uint16_t", - "desc": "Sets `positionEstimationConfigMutable()->w_z_baro_p = value / 100.0f` (constrained 0.0-10.0)", - "units": "Weight * 100" - }, - { - "name": "weightZGPSP", - "ctype": "uint16_t", - "desc": "Sets `positionEstimationConfigMutable()->w_z_gps_p = value / 100.0f` (constrained 0.0-10.0)", - "units": "Weight * 100" - }, - { - "name": "weightZGPSV", - "ctype": "uint16_t", - "desc": "Sets `positionEstimationConfigMutable()->w_z_gps_v = value / 100.0f` (constrained 0.0-10.0)", - "units": "Weight * 100" - }, - { - "name": "weightXYGPSP", - "ctype": "uint16_t", - "desc": "Sets `positionEstimationConfigMutable()->w_xy_gps_p = value / 100.0f` (constrained 0.0-10.0)", - "units": "Weight * 100" - }, - { - "name": "weightXYGPSV", - "ctype": "uint16_t", - "desc": "Sets `positionEstimationConfigMutable()->w_xy_gps_v = value / 100.0f` (constrained 0.0-10.0)", - "units": "Weight * 100" - }, - { - "name": "minSats", - "ctype": "uint8_t", - "desc": "Sets `gpsConfigMutable()->gpsMinSats` (constrained 5-10)", - "units": "Count" - }, - { - "name": "useGPSVelNED", - "ctype": "uint8_t", - "desc": "Legacy flag, ignored", - "units": "Boolean" - } - ] + "MSP_SET_FEATURE": { + "code": 37, + "mspv": 1, + "request": { + "payload": [ + { + "name": "featureMask", + "ctype": "uint32_t", + "desc": "Bitmask: features to enable", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "reply": null, + "notes": "Expects 4 bytes. Updates feature configuration and related settings (e.g., RSSI source).", + "description": "Sets the enabled features using a bitmask. Clears all previous features first." + }, + "MSP_BOARD_ALIGNMENT": { + "code": 38, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "rollAlign", + "ctype": "int16_t", + "desc": "Board alignment roll angle (`boardAlignment()->rollDeciDegrees`). Negative values tilt left.", + "units": "deci-degrees" + }, + { + "name": "pitchAlign", + "ctype": "int16_t", + "desc": "Board alignment pitch angle (`boardAlignment()->pitchDeciDegrees`). Negative values nose down.", + "units": "deci-degrees" + }, + { + "name": "yawAlign", + "ctype": "int16_t", + "desc": "Board alignment yaw angle (`boardAlignment()->yawDeciDegrees`). Negative values rotate counter-clockwise.", + "units": "deci-degrees" + } + ] + }, + "notes": "Ranges are typically -1800 to +1800 (i.e. -180.0Β° to +180.0Β°).", + "description": "Returns the sensor board alignment angles relative to the craft frame." }, - "reply": null, - "notes": "Expects 12 bytes.", - "description": "Sets parameters related to the INAV position estimation fusion weights and GPS minimum satellite count." - }, - "MSP_WP_MISSION_LOAD": { - "code": 18, - "mspv": 1, - "request": { - "payload": [ - { - "name": "missionID", - "ctype": "uint8_t", - "desc": "Reserved for future use, currently ignored", - "units": "" - } - ] + "MSP_SET_BOARD_ALIGNMENT": { + "code": 39, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rollAlign", + "ctype": "int16_t", + "desc": "Sets `boardAlignmentMutable()->rollDeciDegrees`.", + "units": "deci-degrees" + }, + { + "name": "pitchAlign", + "ctype": "int16_t", + "desc": "Sets `boardAlignmentMutable()->pitchDeciDegrees`.", + "units": "deci-degrees" + }, + { + "name": "yawAlign", + "ctype": "int16_t", + "desc": "Sets `boardAlignmentMutable()->yawDeciDegrees`.", + "units": "deci-degrees" + } + ] + }, + "reply": null, + "notes": "Expects 6 bytes encoded as little-endian signed deci-degrees (-1800 to +1800 typical).", + "description": "Sets the sensor board alignment angles." + }, + "MSP_CURRENT_METER_CONFIG": { + "code": 40, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "scale", + "ctype": "int16_t", + "desc": "Current sensor scale factor (`batteryMetersConfig()->current.scale`). Stored in 0.1 mV/A; signed for calibration.", + "units": "0.1 mV/A" + }, + { + "name": "offset", + "ctype": "int16_t", + "desc": "Current sensor offset (`batteryMetersConfig()->current.offset`). Signed millivolt adjustment.", + "units": "mV" + }, + { + "name": "type", + "ctype": "uint8_t", + "desc": "Enum `currentSensor_e` Type of current sensor hardware", + "units": "Enum", + "enum": "currentSensor_e" + }, + { + "name": "capacity", + "ctype": "uint16_t", + "desc": "Battery capacity (constrained 0-65535) (`currentBatteryProfile->capacity.value`). Note: This is legacy, use `MSP2_INAV_BATTERY_CONFIG` for full 32-bit capacity", + "units": "mAh (legacy)" + } + ] + }, + "notes": "Scale and offset are signed values matching `batteryMetersConfig()->current` fields.", + "description": "Retrieves the configuration for the current sensor." }, - "reply": null, - "notes": "Only functional if `NAV_NON_VOLATILE_WAYPOINT_STORAGE` is defined. Requires 1 byte payload. Returns error if loading fails.", - "description": "Commands the FC to load the waypoint mission stored in non-volatile memory (e.g., EEPROM or FlashFS) into the active mission buffer." - }, - "MSP_WP_MISSION_SAVE": { - "code": 19, - "mspv": 1, - "request": { - "payload": [ - { - "name": "missionID", - "ctype": "uint8_t", - "desc": "Reserved for future use, currently ignored", - "units": "" - } - ] + "MSP_SET_CURRENT_METER_CONFIG": { + "code": 41, + "mspv": 1, + "request": { + "payload": [ + { + "name": "scale", + "ctype": "int16_t", + "desc": "Sets `batteryMetersConfigMutable()->current.scale` (0.1 mV/A, signed).", + "units": "0.1 mV/A" + }, + { + "name": "offset", + "ctype": "int16_t", + "desc": "Sets `batteryMetersConfigMutable()->current.offset` (signed millivolts).", + "units": "mV" + }, + { + "name": "type", + "ctype": "uint8_t", + "desc": "Enum `currentSensor_e` Sets `batteryMetersConfigMutable()->current.type`.", + "units": "Enum", + "enum": "currentSensor_e" + }, + { + "name": "capacity", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.value` (truncated to 16 bits)", + "units": "mAh (legacy)" + } + ] + }, + "reply": null, + "notes": "Expects 7 bytes. Signed values use little-endian two's complement.", + "description": "Sets the configuration for the current sensor." + }, + "MSP_MIXER": { + "code": 42, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "mixerMode", + "ctype": "uint8_t", + "desc": "Always 3 (QuadX) in INAV for compatibility", + "units": "", + "value": 3 + } + ] + }, + "notes": "This command is largely obsolete. Mixer configuration is handled differently in INAV (presets, custom mixes). See `MSP2_INAV_MIXER`.", + "description": "Retrieves the mixer type (Legacy, INAV always returns QuadX)." }, - "reply": null, - "notes": "Only functional if `NAV_NON_VOLATILE_WAYPOINT_STORAGE` is defined. Requires 1 byte payload. Returns error if saving fails.", - "description": "Commands the FC to save the currently active waypoint mission from RAM to non-volatile memory (e.g., EEPROM or FlashFS)." - }, - "MSP_WP_GETINFO": { - "code": 20, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "wpCapabilities", - "ctype": "uint8_t", - "desc": "Reserved for future waypoint capabilities flags. Currently always 0", - "units": "", - "value": 0 - }, - { - "name": "maxWaypoints", - "ctype": "uint8_t", - "desc": "Maximum number of waypoints supported (`NAV_MAX_WAYPOINTS`)", - "units": "" - }, - { - "name": "missionValid", - "ctype": "uint8_t", - "desc": "Boolean flag indicating if the current mission in RAM is valid (`isWaypointListValid()`)", - "units": "" - }, - { - "name": "waypointCount", - "ctype": "uint8_t", - "desc": "Number of waypoints currently defined in the mission (`getWaypointCount()`)", - "units": "" - } - ] + "MSP_SET_MIXER": { + "code": 43, + "mspv": 1, + "request": { + "payload": [ + { + "name": "mixerMode", + "ctype": "uint8_t", + "desc": "Mixer mode to set (ignored by INAV)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 1 byte. Calls `mixerUpdateStateFlags()` for potential side effects related to presets.", + "description": "Sets the mixer type (Legacy, ignored by INAV)." + }, + "MSP_RX_CONFIG": { + "code": 44, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "serialRxProvider", + "ctype": "uint8_t", + "desc": "Enum `rxSerialReceiverType_e`. Serial RX provider (`rxConfig()->serialrx_provider`).", + "units": "Enum", + "enum": "rxSerialReceiverType_e" + }, + { + "name": "maxCheck", + "ctype": "uint16_t", + "desc": "Upper channel value threshold for stick commands (`rxConfig()->maxcheck`)", + "units": "PWM" + }, + { + "name": "midRc", + "ctype": "uint16_t", + "desc": "Center channel value (`PWM_RANGE_MIDDLE`, typically 1500)", + "units": "PWM" + }, + { + "name": "minCheck", + "ctype": "uint16_t", + "desc": "Lower channel value threshold for stick commands (`rxConfig()->mincheck`)", + "units": "PWM" + }, + { + "name": "spektrumSatBind", + "ctype": "uint8_t", + "desc": "Spektrum bind pulses (`rxConfig()->spektrum_sat_bind`). 0 if `USE_SPEKTRUM_BIND` disabled.", + "units": "Count/Flag" + }, + { + "name": "rxMinUsec", + "ctype": "uint16_t", + "desc": "Minimum expected pulse width (`rxConfig()->rx_min_usec`)", + "units": "PWM" + }, + { + "name": "rxMaxUsec", + "ctype": "uint16_t", + "desc": "Maximum expected pulse width (`rxConfig()->rx_max_usec`)", + "units": "PWM" + }, + { + "name": "bfCompatRcInterpolation", + "ctype": "uint8_t", + "desc": "BF compatibility. Always 0", + "value": 0 + }, + { + "name": "bfCompatRcInterpolationInt", + "ctype": "uint8_t", + "desc": "BF compatibility. Always 0", + "value": 0 + }, + { + "name": "bfCompatAirModeThreshold", + "ctype": "uint16_t", + "desc": "BF compatibility. Always 0", + "value": 0 + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Reserved/Padding. Always 0", + "value": 0 + }, + { + "name": "reserved2", + "ctype": "uint32_t", + "desc": "Reserved/Padding. Always 0", + "value": 0 + }, + { + "name": "reserved3", + "ctype": "uint8_t", + "desc": "Reserved/Padding. Always 0", + "value": 0 + }, + { + "name": "bfCompatFpvCamAngle", + "ctype": "uint8_t", + "desc": "BF compatibility. Always 0", + "value": 0 + }, + { + "name": "receiverType", + "ctype": "uint8_t", + "desc": "Enum `rxReceiverType_e` Receiver type (Parallel PWM, PPM, Serial) ('rxConfig()->receiverType')", + "units": "Enum", + "enum": "rxReceiverType_e" + } + ] + }, + "notes": "", + "description": "Retrieves receiver configuration settings. Some fields are Betaflight compatibility placeholders." }, - "notes": "", - "description": "Retrieves information about the waypoint mission capabilities and the status of the currently loaded mission." - }, - "MSP_RTH_AND_LAND_CONFIG": { - "code": 21, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "minRthDistance", - "ctype": "uint16_t", - "desc": "Minimum distance from home required for RTH to engage (`navConfig()->general.min_rth_distance`)", - "units": "cm" - }, - { - "name": "rthClimbFirst", - "ctype": "uint8_t", - "desc": "Flag: Climb to RTH altitude before returning (`navConfig()->general.flags.rth_climb_first`)", - "units": "Boolean" - }, - { - "name": "rthClimbIgnoreEmerg", - "ctype": "uint8_t", - "desc": "Flag: Climb even in emergency RTH (`navConfig()->general.flags.rth_climb_ignore_emerg`)", - "units": "Boolean" - }, - { - "name": "rthTailFirst", - "ctype": "uint8_t", - "desc": "Flag: Return tail-first during RTH (`navConfig()->general.flags.rth_tail_first`)", - "units": "Boolean" - }, - { - "name": "rthAllowLanding", - "ctype": "uint8_t", - "desc": "Flag: Allow automatic landing after RTH (`navConfig()->general.flags.rth_allow_landing`)", - "units": "Boolean" - }, - { - "name": "rthAltControlMode", - "ctype": "uint8_t", - "desc": "RTH altitude control mode (`navConfig()->general.flags.rth_alt_control_mode`). WARNING: uses unnamed enum in navigation.h:253 'NAV_RTH_NO_ALT...'", - "units": "Enum", - "enum": "navRthAltControlMode_e" - }, - { - "name": "rthAbortThreshold", - "ctype": "uint16_t", - "desc": "Distance increase threshold to abort RTH (`navConfig()->general.rth_abort_threshold`)", - "units": "cm" - }, - { - "name": "rthAltitude", - "ctype": "uint16_t", - "desc": "Target RTH altitude (`navConfig()->general.rth_altitude`)", - "units": "cm" - }, - { - "name": "landMinAltVspd", - "ctype": "uint16_t", - "desc": "Landing vertical speed at minimum slowdown altitude (`navConfig()->general.land_minalt_vspd`)", - "units": "cm/s" - }, - { - "name": "landMaxAltVspd", - "ctype": "uint16_t", - "desc": "Landing vertical speed at maximum slowdown altitude (`navConfig()->general.land_maxalt_vspd`)", - "units": "cm/s" - }, - { - "name": "landSlowdownMinAlt", - "ctype": "uint16_t", - "desc": "Altitude below which `landMinAltVspd` applies (`navConfig()->general.land_slowdown_minalt`)", - "units": "cm" - }, - { - "name": "landSlowdownMaxAlt", - "ctype": "uint16_t", - "desc": "Altitude above which `landMaxAltVspd` applies (`navConfig()->general.land_slowdown_maxalt`)", - "units": "cm" - }, - { - "name": "emergDescentRate", - "ctype": "uint16_t", - "desc": "Vertical speed during emergency landing descent (`navConfig()->general.emerg_descent_rate`)", - "units": "cm/s" - } - ] - }, - "notes": "", - "description": "Retrieves configuration parameters related to Return-to-Home (RTH) and automatic landing behaviors." - }, - "MSP_SET_RTH_AND_LAND_CONFIG": { - "code": 22, - "mspv": 1, - "request": { - "payload": [ - { - "name": "minRthDistance", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.min_rth_distance`.", - "units": "cm" - }, - { - "name": "rthClimbFirst", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->general.flags.rth_climb_first`.", - "units": "Boolean" - }, - { - "name": "rthClimbIgnoreEmerg", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->general.flags.rth_climb_ignore_emerg`.", - "units": "Boolean" - }, - { - "name": "rthTailFirst", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->general.flags.rth_tail_first`.", - "units": "Boolean" - }, - { - "name": "rthAllowLanding", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->general.flags.rth_allow_landing`.", - "units": "Boolean" - }, - { - "name": "rthAltControlMode", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->general.flags.rth_alt_control_mode`. WARNING: uses unnamed enum in navigation.h:253", - "units": "Enum", - "enum": "navRthAltControlMode_e" - }, - { - "name": "rthAbortThreshold", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.rth_abort_threshold`.", - "units": "cm" - }, - { - "name": "rthAltitude", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.rth_altitude`.", - "units": "cm" - }, - { - "name": "landMinAltVspd", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.land_minalt_vspd`.", - "units": "cm/s" - }, - { - "name": "landMaxAltVspd", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.land_maxalt_vspd`.", - "units": "cm/s" - }, - { - "name": "landSlowdownMinAlt", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.land_slowdown_minalt`.", - "units": "cm" - }, - { - "name": "landSlowdownMaxAlt", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.land_slowdown_maxalt`.", - "units": "cm" - }, - { - "name": "emergDescentRate", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->general.emerg_descent_rate`.", - "units": "cm/s" - } - ] + "MSP_SET_RX_CONFIG": { + "code": 45, + "mspv": 1, + "request": { + "payload": [ + { + "name": "serialRxProvider", + "ctype": "uint8_t", + "desc": "Enum `rxSerialReceiverType_e`. Sets `rxConfigMutable()->serialrx_provider`.", + "units": "Enum", + "enum": "rxSerialReceiverType_e" + }, + { + "name": "maxCheck", + "ctype": "uint16_t", + "desc": "Sets `rxConfigMutable()->maxcheck`.", + "units": "PWM" + }, + { + "name": "midRc", + "ctype": "uint16_t", + "desc": "Ignored (`PWM_RANGE_MIDDLE` is used)", + "units": "PWM" + }, + { + "name": "minCheck", + "ctype": "uint16_t", + "desc": "Sets `rxConfigMutable()->mincheck`.", + "units": "PWM" + }, + { + "name": "spektrumSatBind", + "ctype": "uint8_t", + "desc": "Sets `rxConfigMutable()->spektrum_sat_bind` (if `USE_SPEKTRUM_BIND`).", + "units": "Count/Flag" + }, + { + "name": "rxMinUsec", + "ctype": "uint16_t", + "desc": "Sets `rxConfigMutable()->rx_min_usec`.", + "units": "PWM" + }, + { + "name": "rxMaxUsec", + "ctype": "uint16_t", + "desc": "Sets `rxConfigMutable()->rx_max_usec`.", + "units": "PWM" + }, + { + "name": "bfCompatRcInterpolation", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "bfCompatRcInterpolationInt", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "bfCompatAirModeThreshold", + "ctype": "uint16_t", + "desc": "Ignored" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "reserved2", + "ctype": "uint32_t", + "desc": "Ignored" + }, + { + "name": "reserved3", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "bfCompatFpvCamAngle", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "receiverType", + "ctype": "uint8_t", + "desc": "Enum `rxReceiverType_e` Sets `rxConfigMutable()->receiverType`.", + "units": "Enum", + "enum": "rxReceiverType_e" + } + ] + }, + "reply": null, + "notes": "Expects 24 bytes.", + "description": "Sets receiver configuration settings." + }, + "MSP_LED_COLORS": { + "code": 46, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "hue", + "ctype": "uint16_t", + "desc": "Hue value (0-359)", + "units": "" + }, + { + "name": "saturation", + "ctype": "uint8_t", + "desc": "Saturation value (0-255)", + "units": "" + }, + { + "name": "value", + "ctype": "uint8_t", + "desc": "Value/Brightness (0-255)", + "units": "" + } + ], + "repeating": "LED_CONFIGURABLE_COLOR_COUNT" + }, + "notes": "Only available if `USE_LED_STRIP` is defined.", + "description": "Retrieves the HSV color definitions for configurable LED colors." }, - "reply": null, - "notes": "Expects 21 bytes.", - "description": "Sets configuration parameters related to Return-to-Home (RTH) and automatic landing behaviors." - }, - "MSP_FW_CONFIG": { - "code": 23, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "cruiseThrottle", - "ctype": "uint16_t", - "desc": "Cruise throttle command (`currentBatteryProfile->nav.fw.cruise_throttle`).", - "units": "PWM" - }, - { - "name": "minThrottle", - "ctype": "uint16_t", - "desc": "Minimum throttle during autonomous flight (`currentBatteryProfile->nav.fw.min_throttle`).", - "units": "PWM" - }, - { - "name": "maxThrottle", - "ctype": "uint16_t", - "desc": "Maximum throttle during autonomous flight (`currentBatteryProfile->nav.fw.max_throttle`).", - "units": "PWM" - }, - { - "name": "maxBankAngle", - "ctype": "uint8_t", - "desc": "Maximum bank angle allowed (`navConfig()->fw.max_bank_angle`)", - "units": "degrees" - }, - { - "name": "maxClimbAngle", - "ctype": "uint8_t", - "desc": "Maximum pitch angle during climb (`navConfig()->fw.max_climb_angle`)", - "units": "degrees" - }, - { - "name": "maxDiveAngle", - "ctype": "uint8_t", - "desc": "Maximum negative pitch angle during descent (`navConfig()->fw.max_dive_angle`)", - "units": "degrees" - }, - { - "name": "pitchToThrottle", - "ctype": "uint8_t", - "desc": "Pitch-to-throttle gain (`currentBatteryProfile->nav.fw.pitch_to_throttle`); PWM microseconds per degree (10 units β‰ˆ 1% throttle).", - "units": "us/deg" - }, - { - "name": "loiterRadius", - "ctype": "uint16_t", - "desc": "Default loiter radius (`navConfig()->fw.loiter_radius`).", - "units": "cm" - } - ] + "MSP_SET_LED_COLORS": { + "code": 47, + "mspv": 1, + "request": { + "payload": [ + { + "name": "hue", + "ctype": "uint16_t", + "desc": "Hue value (0-359)", + "units": "" + }, + { + "name": "saturation", + "ctype": "uint8_t", + "desc": "Saturation value (0-255)", + "units": "" + }, + { + "name": "value", + "ctype": "uint8_t", + "desc": "Value/Brightness (0-255)", + "units": "" + } + ], + "repeating": "LED_CONFIGURABLE_COLOR_COUNT" + }, + "reply": null, + "notes": "Only available if `USE_LED_STRIP` is defined. Expects `LED_CONFIGURABLE_COLOR_COUNT * 4` bytes.", + "description": "Sets the HSV color definitions for configurable LED colors." + }, + "MSP_LED_STRIP_CONFIG": { + "code": 48, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "legacyLedConfig", + "ctype": "uint32_t", + "desc": "Packed LED configuration (position, function, overlay, color, direction, params). See C code for bit packing details", + "units": "" + } + ], + "repeating": "LED_MAX_STRIP_LENGTH" + }, + "variable_len": "LED_MAX_STRIP_LENGTH", + "notes": "Only available if `USE_LED_STRIP` is defined. Superseded by `MSP2_INAV_LED_STRIP_CONFIG_EX` which uses a clearer struct.", + "description": "Retrieves the configuration for each LED on the strip (legacy packed format)." }, - "notes": "", - "description": "Retrieves configuration parameters specific to Fixed Wing navigation." - }, - "MSP_SET_FW_CONFIG": { - "code": 24, - "mspv": 1, - "request": { - "payload": [ - { - "name": "cruiseThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->nav.fw.cruise_throttle`.", - "units": "PWM" - }, - { - "name": "minThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->nav.fw.min_throttle`.", - "units": "PWM" - }, - { - "name": "maxThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->nav.fw.max_throttle`.", - "units": "PWM" - }, - { - "name": "maxBankAngle", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->fw.max_bank_angle`.", - "units": "degrees" - }, - { - "name": "maxClimbAngle", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->fw.max_climb_angle`.", - "units": "degrees" - }, - { - "name": "maxDiveAngle", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->fw.max_dive_angle`.", - "units": "degrees" - }, - { - "name": "pitchToThrottle", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->nav.fw.pitch_to_throttle` (PWM microseconds per degree; 10 units β‰ˆ 1% throttle).", - "units": "us/deg" - }, - { - "name": "loiterRadius", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->fw.loiter_radius`.", - "units": "cm" - } - ] + "MSP_SET_LED_STRIP_CONFIG": { + "code": 49, + "mspv": 1, + "request": { + "payload": [ + { + "name": "ledIndex", + "ctype": "uint8_t", + "desc": "Index of the LED to configure (0 to `LED_MAX_STRIP_LENGTH - 1`)", + "units": "" + }, + { + "name": "legacyLedConfig", + "ctype": "uint32_t", + "desc": "Packed LED configuration to set", + "units": "" + } + ] + }, + "reply": null, + "notes": "Only available if `USE_LED_STRIP` is defined. Expects 5 bytes. Calls `reevaluateLedConfig()`. Superseded by `MSP2_INAV_SET_LED_STRIP_CONFIG_EX`.", + "description": "Sets the configuration for a single LED on the strip using the legacy packed format." + }, + "MSP_RSSI_CONFIG": { + "code": 50, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "rssiChannel", + "ctype": "uint8_t", + "desc": "AUX channel index (1-based) used for RSSI, or 0 if disabled (`rxConfig()->rssi_channel`)", + "units": "" + } + ] + }, + "notes": "", + "description": "Retrieves the channel used for analog RSSI input." }, - "reply": null, - "notes": "Expects 12 bytes.", - "description": "Sets configuration parameters specific to Fixed Wing navigation." - }, - "MSP_MODE_RANGES": { - "code": 34, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "modePermanentId", - "ctype": "uint8_t", - "desc": "Permanent ID of the flight mode (maps to `boxId` via `findBoxByActiveBoxId`). 0 if entry unused", - "units": "ID" - }, - { - "name": "auxChannelIndex", - "ctype": "uint8_t", - "desc": "0-based index of the AUX channel used for activation", - "units": "Index" - }, - { - "name": "rangeStartStep", - "ctype": "uint8_t", - "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", - "units": "step" - }, - { - "name": "rangeEndStep", - "ctype": "uint8_t", - "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", - "units": "step" - } - ], - "repeating": "MAX_MODE_ACTIVATION_CONDITION_COUNT" + "MSP_SET_RSSI_CONFIG": { + "code": 51, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rssiChannel", + "ctype": "uint8_t", + "desc": "AUX channel index (1-based) to use for RSSI, or 0 to disable", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 1 byte. Input value is constrained 0 to `MAX_SUPPORTED_RC_CHANNEL_COUNT`. Updates the effective RSSI source.", + "description": "Sets the channel used for analog RSSI input." + }, + "MSP_ADJUSTMENT_RANGES": { + "code": 52, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "adjustmentIndex", + "ctype": "uint8_t", + "desc": "Index of the adjustment slot (0 to `MAX_SIMULTANEOUS_ADJUSTMENT_COUNT - 1`)", + "units": "" + }, + { + "name": "auxChannelIndex", + "ctype": "uint8_t", + "desc": "0-based index of the AUX channel controlling the adjustment value", + "units": "" + }, + { + "name": "rangeStartStep", + "ctype": "uint8_t", + "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", + "units": "step" + }, + { + "name": "rangeEndStep", + "ctype": "uint8_t", + "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", + "units": "step" + }, + { + "name": "adjustmentFunction", + "ctype": "uint8_t", + "desc": "Function/parameter being adjusted (see `adjustmentFunction_e`).", + "units": "", + "enum": "adjustmentFunction_e" + }, + { + "name": "auxSwitchChannelIndex", + "ctype": "uint8_t", + "desc": "0-based index of the AUX channel acting as an enable switch (or 0 if always enabled)", + "units": "" + } + ], + "repeating": "MAX_ADJUSTMENT_RANGE_COUNT" + }, + "notes": "See `adjustmentRange_t`.", + "description": "Returns all defined RC adjustment ranges (tuning via aux channels)." }, - "notes": "The number of steps and mapping to PWM values depends on internal range calculations.", - "description": "Returns all defined mode activation ranges (aux channel assignments for flight modes)." - }, - "MSP_SET_MODE_RANGE": { - "code": 35, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rangeIndex", - "ctype": "uint8_t", - "desc": "Index of the mode range to set (0 to `MAX_MODE_ACTIVATION_CONDITION_COUNT - 1`)", - "units": "Index" - }, - { - "name": "modePermanentId", - "ctype": "uint8_t", - "desc": "Permanent ID of the flight mode to assign", - "units": "ID" - }, - { - "name": "auxChannelIndex", - "ctype": "uint8_t", - "desc": "0-based index of the AUX channel", - "units": "Index" - }, - { - "name": "rangeStartStep", - "ctype": "uint8_t", - "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", - "units": "step" - }, - { - "name": "rangeEndStep", - "ctype": "uint8_t", - "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", - "units": "step" - } - ] + "MSP_SET_ADJUSTMENT_RANGE": { + "code": 53, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rangeIndex", + "ctype": "uint8_t", + "desc": "Index of the adjustment range to set (0 to `MAX_ADJUSTMENT_RANGE_COUNT - 1`)", + "units": "" + }, + { + "name": "adjustmentIndex", + "ctype": "uint8_t", + "desc": "Adjustment slot index (0 to `MAX_SIMULTANEOUS_ADJUSTMENT_COUNT - 1`)", + "units": "" + }, + { + "name": "auxChannelIndex", + "ctype": "uint8_t", + "desc": "0-based index of the control AUX channel", + "units": "" + }, + { + "name": "rangeStartStep", + "ctype": "uint8_t", + "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", + "units": "step" + }, + { + "name": "rangeEndStep", + "ctype": "uint8_t", + "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", + "units": "step" + }, + { + "name": "adjustmentFunction", + "ctype": "uint8_t", + "desc": "Function/parameter being adjusted.", + "units": "", + "enum": "adjustmentFunction_e" + }, + { + "name": "auxSwitchChannelIndex", + "ctype": "uint8_t", + "desc": "0-based index of the enable switch AUX channel (or 0)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 7 bytes. Returns error if `rangeIndex` or `adjustmentIndex` is invalid.", + "description": "Sets a single RC adjustment range configuration by its index." + }, + "MSP_CF_SERIAL_CONFIG": { + "code": 54, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`. Use `MSP2_COMMON_SERIAL_CONFIG`.", + "description": "Deprecated command to get serial port configuration." + }, + "MSP_SET_CF_SERIAL_CONFIG": { + "code": 55, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`. Use `MSP2_COMMON_SET_SERIAL_CONFIG`.", + "description": "Deprecated command to set serial port configuration." + }, + "MSP_VOLTAGE_METER_CONFIG": { + "code": 56, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "vbatScale", + "ctype": "uint8_t", + "desc": "Voltage sensor scale factor / 10 (`batteryMetersConfig()->voltage.scale / 10`). 0 if `USE_ADC` disabled", + "units": "Scale / 10" + }, + { + "name": "vbatMinCell", + "ctype": "uint8_t", + "desc": "Minimum cell voltage / 10 (`currentBatteryProfile->voltage.cellMin / 10`). 0 if `USE_ADC` disabled", + "units": "0.1V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint8_t", + "desc": "Maximum cell voltage / 10 (`currentBatteryProfile->voltage.cellMax / 10`). 0 if `USE_ADC` disabled", + "units": "0.1V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint8_t", + "desc": "Warning cell voltage / 10 (`currentBatteryProfile->voltage.cellWarning / 10`). 0 if `USE_ADC` disabled", + "units": "0.1V" + } + ] + }, + "notes": "Superseded by `MSP2_INAV_BATTERY_CONFIG`.", + "description": "Retrieves legacy voltage meter configuration (scaled values)." }, - "reply": null, - "notes": "Expects 5 bytes. Updates the mode configuration and recalculates used mode flags. Returns error if `rangeIndex` or `modePermanentId` is invalid.", - "description": "Sets a single mode activation range by its index." - }, - "MSP_FEATURE": { - "code": 36, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "featureMask", - "ctype": "uint32_t", - "desc": "Bitmask: active features (see `featureMask()`)", - "units": "Bitmask", - "bitmask": true - } - ] + "MSP_SET_VOLTAGE_METER_CONFIG": { + "code": 57, + "mspv": 1, + "request": { + "payload": [ + { + "name": "vbatScale", + "ctype": "uint8_t", + "desc": "Sets `batteryMetersConfigMutable()->voltage.scale = value * 10` (if `USE_ADC`)", + "units": "Scale / 10" + }, + { + "name": "vbatMinCell", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin = value * 10` (if `USE_ADC`)", + "units": "0.1V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax = value * 10` (if `USE_ADC`)", + "units": "0.1V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning = value * 10` (if `USE_ADC`)", + "units": "0.1V" + } + ] + }, + "reply": null, + "notes": "Expects 4 bytes. Superseded by `MSP2_INAV_SET_BATTERY_CONFIG`.", + "description": "Sets legacy voltage meter configuration (scaled values)." + }, + "MSP_SONAR_ALTITUDE": { + "code": 58, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "rangefinderAltitude", + "ctype": "int32_t", + "desc": "Latest altitude reading from the rangefinder (`rangefinderGetLatestAltitude()`). 0 if `USE_RANGEFINDER` disabled or no reading.", + "units": "cm" + } + ] + }, + "notes": "", + "description": "Retrieves the altitude measured by the primary rangefinder (sonar or lidar)." + }, + "MSP_RX_MAP": { + "code": 64, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "rcMap", + "desc": "Array defining the mapping from input channel index to logical function (Roll, Pitch, Yaw, Throttle, Aux1...)", + "ctype": "uint8_t", + "array": true, + "array_size": 4, + "array_size_define": "MAX_MAPPABLE_RX_INPUTS", + "units": "" + } + ] + }, + "notes": "`MAX_MAPPABLE_RX_INPUTS` is currently 4 (Roll, Pitch, Yaw, Throttle).", + "description": "Retrieves the RC channel mapping array (AETR, etc.)." }, - "notes": "Feature bits are defined in `feature.h`.", - "description": "Returns a bitmask of enabled features." - }, - "MSP_SET_FEATURE": { - "code": 37, - "mspv": 1, - "request": { - "payload": [ - { - "name": "featureMask", - "ctype": "uint32_t", - "desc": "Bitmask: features to enable", - "units": "Bitmask", - "bitmask": true - } - ] + "MSP_SET_RX_MAP": { + "code": 65, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rcMap", + "desc": "Array defining the new channel mapping", + "ctype": "uint8_t", + "array": true, + "array_size": 4, + "array_size_define": "MAX_MAPPABLE_RX_INPUTS", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects `MAX_MAPPABLE_RX_INPUTS` bytes (currently 4).", + "description": "Sets the RC channel mapping array." + }, + "MSP_REBOOT": { + "code": 68, + "mspv": 1, + "request": null, + "reply": null, + "notes": "The FC sends an ACK *before* rebooting. The `mspPostProcessFn` is set to `mspRebootFn` to perform the reboot after the reply is sent. Will fail if the craft is armed.", + "description": "Commands the flight controller to reboot." + }, + "MSP_DATAFLASH_SUMMARY": { + "code": 70, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "flashReady", + "ctype": "uint8_t", + "desc": "Boolean: 1 if flash chip is ready, 0 otherwise. (`flashIsReady()`). 0 if `USE_FLASHFS` disabled", + "units": "" + }, + { + "name": "sectorCount", + "ctype": "uint32_t", + "desc": "Total number of sectors on the flash chip (`geometry->sectors`). 0 if `USE_FLASHFS` disabled", + "units": "" + }, + { + "name": "totalSize", + "ctype": "uint32_t", + "desc": "Total size of the flash chip in bytes (`geometry->totalSize`). 0 if `USE_FLASHFS` disabled", + "units": "" + }, + { + "name": "usedSize", + "ctype": "uint32_t", + "desc": "Currently used size in bytes (FlashFS offset) (`flashfsGetOffset()`). 0 if `USE_FLASHFS` disabled", + "units": "" + } + ] + }, + "notes": "Requires `USE_FLASHFS`.", + "description": "Retrieves summary information about the onboard dataflash chip (if present and used for Blackbox via FlashFS)." }, - "reply": null, - "notes": "Expects 4 bytes. Updates feature configuration and related settings (e.g., RSSI source).", - "description": "Sets the enabled features using a bitmask. Clears all previous features first." - }, - "MSP_BOARD_ALIGNMENT": { - "code": 38, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "rollAlign", - "ctype": "int16_t", - "desc": "Board alignment roll angle (`boardAlignment()->rollDeciDegrees`). Negative values tilt left.", - "units": "deci-degrees" - }, - { - "name": "pitchAlign", - "ctype": "int16_t", - "desc": "Board alignment pitch angle (`boardAlignment()->pitchDeciDegrees`). Negative values nose down.", - "units": "deci-degrees" - }, - { - "name": "yawAlign", - "ctype": "int16_t", - "desc": "Board alignment yaw angle (`boardAlignment()->yawDeciDegrees`). Negative values rotate counter-clockwise.", - "units": "deci-degrees" - } - ] - }, - "notes": "Ranges are typically -1800 to +1800 (i.e. -180.0Β° to +180.0Β°).", - "description": "Returns the sensor board alignment angles relative to the craft frame." - }, - "MSP_SET_BOARD_ALIGNMENT": { - "code": 39, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rollAlign", - "ctype": "int16_t", - "desc": "Sets `boardAlignmentMutable()->rollDeciDegrees`.", - "units": "deci-degrees" - }, - { - "name": "pitchAlign", - "ctype": "int16_t", - "desc": "Sets `boardAlignmentMutable()->pitchDeciDegrees`.", - "units": "deci-degrees" - }, - { - "name": "yawAlign", - "ctype": "int16_t", - "desc": "Sets `boardAlignmentMutable()->yawDeciDegrees`.", - "units": "deci-degrees" - } - ] + "MSP_DATAFLASH_READ": { + "code": 71, + "mspv": 1, + "request": { + "payload": [ + { + "name": "address", + "ctype": "uint32_t", + "desc": "Starting address to read from within the FlashFS volume", + "units": "" + }, + { + "name": "size", + "ctype": "uint16_t", + "desc": "(Optional) Number of bytes to read. Defaults to 128 if not provided", + "units": "", + "optional": true + } + ] + }, + "reply": { + "payload": [ + { + "name": "address", + "ctype": "uint32_t", + "desc": "The starting address from which data was actually read", + "units": "" + }, + { + "name": "data", + "desc": "The data read from flash. Length is MIN(requested size, remaining buffer space, remaining flashfs data)", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_FLASHFS`. Read length may be truncated by buffer size or end of flashfs volume.", + "description": "Reads a block of data from the onboard dataflash (FlashFS)." + }, + "MSP_DATAFLASH_ERASE": { + "code": 72, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Requires `USE_FLASHFS`. This is a potentially long operation. Use with caution.", + "description": "Erases the entire onboard dataflash chip (FlashFS volume)." + }, + "MSP_LOOP_TIME": { + "code": 73, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "looptime", + "ctype": "uint16_t", + "desc": "Configured loop time (`gyroConfig()->looptime`)", + "units": "PWM" + } + ] + }, + "notes": "This is the *configured* target loop time, not necessarily the *actual* measured cycle time (see `MSP_STATUS`).", + "description": "Retrieves the configured loop time (PID loop frequency denominator)." }, - "reply": null, - "notes": "Expects 6 bytes encoded as little-endian signed deci-degrees (-1800 to +1800 typical).", - "description": "Sets the sensor board alignment angles." - }, - "MSP_CURRENT_METER_CONFIG": { - "code": 40, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "scale", - "ctype": "int16_t", - "desc": "Current sensor scale factor (`batteryMetersConfig()->current.scale`). Stored in 0.1 mV/A; signed for calibration.", - "units": "0.1 mV/A" - }, - { - "name": "offset", - "ctype": "int16_t", - "desc": "Current sensor offset (`batteryMetersConfig()->current.offset`). Signed millivolt adjustment.", - "units": "mV" - }, - { - "name": "type", - "ctype": "uint8_t", - "desc": "Enum `currentSensor_e` Type of current sensor hardware", - "units": "Enum", - "enum": "currentSensor_e" - }, - { - "name": "capacity", - "ctype": "uint16_t", - "desc": "Battery capacity (constrained 0-65535) (`currentBatteryProfile->capacity.value`). Note: This is legacy, use `MSP2_INAV_BATTERY_CONFIG` for full 32-bit capacity", - "units": "mAh (legacy)" - } - ] + "MSP_SET_LOOP_TIME": { + "code": 74, + "mspv": 1, + "request": { + "payload": [ + { + "name": "looptime", + "ctype": "uint16_t", + "desc": "New loop time to set (`gyroConfigMutable()->looptime`)", + "units": "PWM" + } + ] + }, + "reply": null, + "notes": "Expects 2 bytes.", + "description": "Sets the configured loop time." + }, + "MSP_FAILSAFE_CONFIG": { + "code": 75, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "failsafeDelay", + "ctype": "uint8_t", + "desc": "Delay before failsafe stage 1 activates (`failsafeConfig()->failsafe_delay`)", + "units": "0.1s" + }, + { + "name": "failsafeOffDelay", + "ctype": "uint8_t", + "desc": "Delay after signal recovery before returning control (`failsafeConfig()->failsafe_off_delay`)", + "units": "0.1s" + }, + { + "name": "failsafeThrottle", + "ctype": "uint16_t", + "desc": "Throttle level during failsafe stage 2 (`currentBatteryProfile->failsafe_throttle`)", + "units": "PWM" + }, + { + "name": "legacyKillSwitch", + "ctype": "uint8_t", + "desc": "Legacy flag, always 0", + "value": 0 + }, + { + "name": "failsafeThrottleLowDelay", + "ctype": "uint16_t", + "desc": "Delay for throttle-based failsafe detection (`failsafeConfig()->failsafe_throttle_low_delay`). Units of 0.1 seconds.", + "units": "0.1s" + }, + { + "name": "failsafeProcedure", + "ctype": "uint8_t", + "desc": "Enum `failsafeProcedure_e` Failsafe procedure (Drop, RTH, Land, etc.) ('failsafeConfig()->failsafe_procedure')", + "units": "Enum", + "enum": "failsafeProcedure_e" + }, + { + "name": "failsafeRecoveryDelay", + "ctype": "uint8_t", + "desc": "Delay after RTH finishes before attempting recovery (`failsafeConfig()->failsafe_recovery_delay`)", + "units": "0.1s" + }, + { + "name": "failsafeFWRollAngle", + "ctype": "int16_t", + "desc": "Fixed-wing failsafe roll angle (`failsafeConfig()->failsafe_fw_roll_angle`). Signed deci-degrees.", + "units": "deci-degrees" + }, + { + "name": "failsafeFWPitchAngle", + "ctype": "int16_t", + "desc": "Fixed-wing failsafe pitch angle (`failsafeConfig()->failsafe_fw_pitch_angle`). Signed deci-degrees.", + "units": "deci-degrees" + }, + { + "name": "failsafeFWYawRate", + "ctype": "int16_t", + "desc": "Fixed-wing failsafe yaw rate (`failsafeConfig()->failsafe_fw_yaw_rate`). Signed degrees per second.", + "units": "deg/s" + }, + { + "name": "failsafeStickThreshold", + "ctype": "uint16_t", + "desc": "Stick movement threshold to exit failsafe (`failsafeConfig()->failsafe_stick_motion_threshold`)", + "units": "PWM units" + }, + { + "name": "failsafeMinDistance", + "ctype": "uint16_t", + "desc": "Minimum distance from home for RTH failsafe (`failsafeConfig()->failsafe_min_distance`). Units of centimeters.", + "units": "cm" + }, + { + "name": "failsafeMinDistanceProc", + "ctype": "uint8_t", + "desc": "Enum `failsafeProcedure_e` Failsafe procedure if below min distance ('failsafeConfig()->failsafe_min_distance_procedure')", + "units": "Enum", + "enum": "failsafeProcedure_e" + } + ] + }, + "notes": "", + "description": "Retrieves the failsafe configuration settings." }, - "notes": "Scale and offset are signed values matching `batteryMetersConfig()->current` fields.", - "description": "Retrieves the configuration for the current sensor." - }, - "MSP_SET_CURRENT_METER_CONFIG": { - "code": 41, - "mspv": 1, - "request": { - "payload": [ - { - "name": "scale", - "ctype": "int16_t", - "desc": "Sets `batteryMetersConfigMutable()->current.scale` (0.1 mV/A, signed).", - "units": "0.1 mV/A" - }, - { - "name": "offset", - "ctype": "int16_t", - "desc": "Sets `batteryMetersConfigMutable()->current.offset` (signed millivolts).", - "units": "mV" + "MSP_SET_FAILSAFE_CONFIG": { + "code": 76, + "mspv": 1, + "request": { + "payload": [ + { + "name": "failsafeDelay", + "ctype": "uint8_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_delay`.", + "units": "0.1s" + }, + { + "name": "failsafeOffDelay", + "ctype": "uint8_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_off_delay`.", + "units": "0.1s" + }, + { + "name": "failsafeThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->failsafe_throttle`.", + "units": "PWM" + }, + { + "name": "legacyKillSwitch", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "failsafeThrottleLowDelay", + "ctype": "uint16_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_throttle_low_delay`. Units of 0.1 seconds.", + "units": "0.1s" + }, + { + "name": "failsafeProcedure", + "ctype": "uint8_t", + "desc": "Enum `failsafeProcedure_e`. Sets `failsafeConfigMutable()->failsafe_procedure`.", + "units": "Enum", + "enum": "failsafeProcedure_e" + }, + { + "name": "failsafeRecoveryDelay", + "ctype": "uint8_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_recovery_delay`.", + "units": "0.1s" + }, + { + "name": "failsafeFWRollAngle", + "ctype": "int16_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_fw_roll_angle`. Signed deci-degrees.", + "units": "deci-degrees" + }, + { + "name": "failsafeFWPitchAngle", + "ctype": "int16_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_fw_pitch_angle`. Signed deci-degrees.", + "units": "deci-degrees" + }, + { + "name": "failsafeFWYawRate", + "ctype": "int16_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_fw_yaw_rate`. Signed degrees per second.", + "units": "deg/s" + }, + { + "name": "failsafeStickThreshold", + "ctype": "uint16_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_stick_motion_threshold`.", + "units": "PWM units" + }, + { + "name": "failsafeMinDistance", + "ctype": "uint16_t", + "desc": "Sets `failsafeConfigMutable()->failsafe_min_distance`. Units of centimeters.", + "units": "cm" + }, + { + "name": "failsafeMinDistanceProc", + "ctype": "uint8_t", + "desc": "Enum `failsafeProcedure_e`. Sets `failsafeConfigMutable()->failsafe_min_distance_procedure`.", + "units": "Enum", + "enum": "failsafeProcedure_e" + } + ] + }, + "reply": null, + "notes": "Expects 20 bytes.", + "description": "Sets the failsafe configuration settings." + }, + "MSP_SDCARD_SUMMARY": { + "code": 79, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "sdCardSupported", + "ctype": "uint8_t", + "desc": "Bitmask: Bit 0 = 1 if SD card support compiled in (`USE_SDCARD`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "sdCardState", + "ctype": "uint8_t", + "desc": "Enum (`mspSDCardState_e`): Current state (Not Present, Fatal, Card Init, FS Init, Ready). 0 if `USE_SDCARD` disabled", + "units": "", + "enum": "mspSDCardState_e" + }, + { + "name": "fsError", + "ctype": "uint8_t", + "desc": "Last filesystem error code (`afatfs_getLastError()`). 0 if `USE_SDCARD` disabled", + "units": "" + }, + { + "name": "freeSpaceKB", + "ctype": "uint32_t", + "desc": "Free space in KiB (`afatfs_getContiguousFreeSpace() / 1024`). 0 if `USE_SDCARD` disabled", + "units": "" + }, + { + "name": "totalSpaceKB", + "ctype": "uint32_t", + "desc": "Total space in KiB (`sdcard_getMetadata()->numBlocks / 2`). 0 if `USE_SDCARD` disabled", + "units": "" + } + ] + }, + "notes": "Requires `USE_SDCARD` and `USE_ASYNCFATFS`.", + "description": "Retrieves summary information about the SD card status and filesystem." + }, + "MSP_BLACKBOX_CONFIG": { + "code": 80, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "blackboxDevice", + "ctype": "uint8_t", + "desc": "Always 0 (API no longer supported)", + "units": "", + "value": 0 + }, + { + "name": "blackboxRateNum", + "ctype": "uint8_t", + "desc": "Always 0", + "units": "", + "value": 0 + }, + { + "name": "blackboxRateDenom", + "ctype": "uint8_t", + "desc": "Always 0", + "units": "", + "value": 0 + }, + { + "name": "blackboxPDenom", + "ctype": "uint8_t", + "desc": "Always 0", + "units": "", + "value": 0 + } + ] + }, + "notes": "Returns fixed zero values. Use `MSP2_BLACKBOX_CONFIG`.", + "description": "Legacy command to retrieve Blackbox configuration. Superseded by `MSP2_BLACKBOX_CONFIG`." + }, + "MSP_SET_BLACKBOX_CONFIG": { + "code": 81, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in `fc_msp.c`. Use `MSP2_SET_BLACKBOX_CONFIG`.", + "description": "Legacy command to set Blackbox configuration. Superseded by `MSP2_SET_BLACKBOX_CONFIG`." + }, + "MSP_TRANSPONDER_CONFIG": { + "code": 82, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`.", + "description": "Get VTX Transponder settings (likely specific to RaceFlight/Betaflight, not standard INAV VTX)." + }, + "MSP_SET_TRANSPONDER_CONFIG": { + "code": 83, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`.", + "description": "Set VTX Transponder settings." + }, + "MSP_OSD_CONFIG": { + "code": 84, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "osdDriverType", + "ctype": "uint8_t", + "desc": "Enum `osdDriver_e`: `OSD_DRIVER_MAX7456` if `USE_OSD`, else `OSD_DRIVER_NONE`.", + "units": "Enum", + "enum": "osdDriver_e" + }, + { + "name": "videoSystem", + "ctype": "uint8_t", + "desc": "Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`). Sent even if OSD disabled", + "units": "Enum", + "enum": "videoSystem_e" + }, + { + "name": "units", + "ctype": "uint8_t", + "desc": "Enum `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`). Sent even if OSD disabled", + "units": "Enum", + "enum": "osd_unit_e" + }, + { + "name": "rssiAlarm", + "ctype": "uint8_t", + "desc": "RSSI alarm threshold (`osdConfig()->rssi_alarm`). Sent even if OSD disabled", + "units": "%" + }, + { + "name": "capAlarm", + "ctype": "uint16_t", + "desc": "Capacity alarm threshold (`currentBatteryProfile->capacity.warning`). Truncated to 16 bits. Sent even if OSD disabled.", + "units": "mAh/mWh" + }, + { + "name": "timerAlarm", + "ctype": "uint16_t", + "desc": "Timer alarm threshold in minutes (`osdConfig()->time_alarm`). Sent even if OSD disabled.", + "units": "minutes" + }, + { + "name": "altAlarm", + "ctype": "uint16_t", + "desc": "Altitude alarm threshold (`osdConfig()->alt_alarm`). Sent even if OSD disabled", + "units": "meters" + }, + { + "name": "distAlarm", + "ctype": "uint16_t", + "desc": "Distance alarm threshold (`osdConfig()->dist_alarm`). Sent even if OSD disabled", + "units": "meters" + }, + { + "name": "negAltAlarm", + "ctype": "uint16_t", + "desc": "Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`). Sent even if OSD disabled", + "units": "meters" + }, + { + "name": "itemPositions", + "desc": "Packed X/Y position for each OSD item on screen 0 (`osdLayoutsConfig()->item_pos[0][i]`). Sent even if OSD disabled", + "ctype": "uint16_t", + "array": true, + "array_size": 0, + "array_size_define": "OSD_ITEM_COUNT", + "units": "packed" + } + ] + }, + "variable_len": true, + "notes": "1 byte if `USE_OSD` disabled; full payload (1 + fields + 2*OSD_ITEM_COUNT bytes) otherwise.", + "description": "Retrieves OSD configuration settings and layout for screen 0. Coordinates are packed as `(Y << 8) | X`. When `USE_OSD` is not compiled in, only `osdDriverType` = `OSD_DRIVER_NONE` is returned." + }, + "MSP_SET_OSD_CONFIG": { + "code": 85, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Requires `USE_OSD`. Distinguishes formats based on the first byte. Format 1 requires at least 10 bytes. Format 2 requires 3 bytes. Triggers an OSD redraw. See `MSP2_INAV_OSD_SET_*` for more advanced control.", + "description": "Sets OSD configuration or a single item's position on screen 0.", + "variants": { + "dataSize >= 10": { + "description": "dataSize >= 10", + "request": { + "payload": [ + { + "name": "selector", + "ctype": "uint8_t", + "desc": "Must be 0xFF (-1) to indicate a configuration update.", + "value": 255 + }, + { + "name": "videoSystem", + "ctype": "uint8_t", + "desc": "Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`).", + "units": "Enum", + "enum": "videoSystem_e" + }, + { + "name": "units", + "ctype": "uint8_t", + "desc": "Enum `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`).", + "units": "Enum", + "enum": "osd_unit_e" + }, + { + "name": "rssiAlarm", + "ctype": "uint8_t", + "desc": "RSSI alarm threshold (`osdConfig()->rssi_alarm`).", + "units": "%" + }, + { + "name": "capAlarm", + "ctype": "uint16_t", + "desc": "Capacity alarm threshold (`currentBatteryProfile->capacity.warning`). Truncated to 16 bits.", + "units": "mAh/mWh" + }, + { + "name": "timerAlarm", + "ctype": "uint16_t", + "desc": "Timer alarm threshold in minutes (`osdConfig()->time_alarm`).", + "units": "minutes" + }, + { + "name": "altAlarm", + "ctype": "uint16_t", + "desc": "Altitude alarm threshold (`osdConfig()->alt_alarm`).", + "units": "meters" + }, + { + "name": "distAlarm", + "ctype": "uint16_t", + "desc": "Distance alarm threshold (`osdConfig()->dist_alarm`). Optional trailing field.", + "units": "meters", + "optional": true + }, + { + "name": "negAltAlarm", + "ctype": "uint16_t", + "desc": "Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`). Optional trailing field.", + "units": "meters", + "optional": true + } + ] + }, + "reply": null }, - { - "name": "type", - "ctype": "uint8_t", - "desc": "Enum `currentSensor_e` Sets `batteryMetersConfigMutable()->current.type`.", - "units": "Enum", - "enum": "currentSensor_e" + "dataSize == 3": { + "description": "Single item position update", + "request": { + "payload": [ + { + "name": "itemIndex", + "ctype": "uint8_t", + "desc": "Index of the OSD item to update (0 to `OSD_ITEM_COUNT - 1`).", + "units": "Index" + }, + { + "name": "itemPosition", + "ctype": "uint16_t", + "desc": "Packed X/Y position (`(Y << 8) | X`) for the specified item.", + "units": "packed" + } + ] }, - { - "name": "capacity", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.value` (truncated to 16 bits)", - "units": "mAh (legacy)" + "reply": null } - ] + } }, - "reply": null, - "notes": "Expects 7 bytes. Signed values use little-endian two's complement.", - "description": "Sets the configuration for the current sensor." - }, - "MSP_MIXER": { - "code": 42, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "mixerMode", - "ctype": "uint8_t", - "desc": "Always 3 (QuadX) in INAV for compatibility", - "units": "", - "value": 3 + "MSP_OSD_CHAR_READ": { + "code": 86, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`. Requires direct hardware access, typically done via DisplayPort.", + "description": "Reads character data from the OSD font memory." + }, + "MSP_OSD_CHAR_WRITE": { + "code": 87, + "mspv": 1, + "request": null, + "reply": null, + "variable_len": true, + "notes": "Requires `USE_OSD`. Minimum payload is `OSD_CHAR_VISIBLE_BYTES + 1` (8-bit address + 54 bytes). Payload size determines the address width and whether the extra metadata bytes are present. Writes characters via `displayWriteFontCharacter()`.", + "description": "Writes character data to the OSD font memory.", + "variants": { + "payloadSize >= OSD_CHAR_BYTES + 2 (>=66 bytes)": { + "description": "16-bit character index with full 64-byte payload (visible + metadata).", + "request": { + "payload": [ + { + "name": "address", + "ctype": "uint16_t", + "desc": "Character slot index (0-1023)." + }, + { + "name": "charData", + "desc": "All 64 bytes, including driver metadata.", + "ctype": "uint8_t", + "array": true, + "array_size": 64, + "array_size_define": "OSD_CHAR_BYTES" + } + ] + }, + "reply": null + }, + "payloadSize == OSD_CHAR_BYTES + 1 (65 bytes)": { + "description": "8-bit character index with full 64-byte payload.", + "request": { + "payload": [ + { + "name": "address", + "ctype": "uint8_t", + "desc": "Character slot index (0-255)." + }, + { + "name": "charData", + "desc": "All 64 bytes, including driver metadata.", + "ctype": "uint8_t", + "array": true, + "array_size": 64, + "array_size_define": "OSD_CHAR_BYTES" + } + ] + }, + "reply": null + }, + "payloadSize == OSD_CHAR_VISIBLE_BYTES + 2 (56 bytes)": { + "description": "16-bit character index with only the 54 visible bytes.", + "request": { + "payload": [ + { + "name": "address", + "ctype": "uint16_t", + "desc": "Character slot index (0-1023)." + }, + { + "name": "charData", + "desc": "Visible pixel data only (no metadata).", + "ctype": "uint8_t", + "array": true, + "array_size": 54, + "array_size_define": "OSD_CHAR_VISIBLE_BYTES" + } + ] + }, + "reply": null + }, + "payloadSize == OSD_CHAR_VISIBLE_BYTES + 1 (55 bytes)": { + "description": "8-bit character index with only the 54 visible bytes.", + "request": { + "payload": [ + { + "name": "address", + "ctype": "uint8_t", + "desc": "Character slot index (0-255)." + }, + { + "name": "charData", + "desc": "Visible pixel data only (no metadata).", + "ctype": "uint8_t", + "array": true, + "array_size": 54, + "array_size_define": "OSD_CHAR_VISIBLE_BYTES" + } + ] + }, + "reply": null } - ] + } }, - "notes": "This command is largely obsolete. Mixer configuration is handled differently in INAV (presets, custom mixes). See `MSP2_INAV_MIXER`.", - "description": "Retrieves the mixer type (Legacy, INAV always returns QuadX)." - }, - "MSP_SET_MIXER": { - "code": 43, - "mspv": 1, - "request": { - "payload": [ - { - "name": "mixerMode", - "ctype": "uint8_t", - "desc": "Mixer mode to set (ignored by INAV)", - "units": "" + "MSP_VTX_CONFIG": { + "code": 88, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "vtxDeviceType", + "ctype": "uint8_t", + "desc": "Enum (`vtxDevType_e`): Type of VTX device detected/configured. `VTXDEV_UNKNOWN` if none", + "units": "", + "enum": "vtxDevType_e" + }, + { + "name": "band", + "ctype": "uint8_t", + "desc": "VTX band number (from `vtxSettingsConfig`)", + "units": "" + }, + { + "name": "channel", + "ctype": "uint8_t", + "desc": "VTX channel number (from `vtxSettingsConfig`)", + "units": "" + }, + { + "name": "power", + "ctype": "uint8_t", + "desc": "VTX power level index (from `vtxSettingsConfig()`).", + "units": "" + }, + { + "name": "pitMode", + "ctype": "uint8_t", + "desc": "Boolean: 1 if VTX is currently in pit mode, 0 otherwise.", + "units": "" + }, + { + "name": "vtxReady", + "ctype": "uint8_t", + "desc": "Boolean: 1 if VTX device reported ready, 0 otherwise", + "units": "" + }, + { + "name": "lowPowerDisarm", + "ctype": "uint8_t", + "desc": "Enum `vtxLowerPowerDisarm_e`: Low-power behaviour while disarmed (`vtxSettingsConfig()->lowPowerDisarm`).", + "units": "Enum", + "enum": "vtxLowerPowerDisarm_e" + }, + { + "name": "vtxTableAvailable", + "ctype": "uint8_t", + "desc": "Boolean: 1 if VTX tables (band/power) are available for query", + "units": "" + }, + { + "name": "bandCount", + "ctype": "uint8_t", + "desc": "Number of bands supported by the VTX device", + "units": "" + }, + { + "name": "channelCount", + "ctype": "uint8_t", + "desc": "Number of channels per band supported by the VTX device", + "units": "" + }, + { + "name": "powerCount", + "ctype": "uint8_t", + "desc": "Number of power levels supported by the VTX device", + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Returns 1 byte (`VTXDEV_UNKNOWN`) when no VTX is detected or `USE_VTX_CONTROL` is disabled; otherwise sends full payload. BF compatibility field `frequency` (uint16) is missing compared to some BF versions. Use `MSP_VTXTABLE_BAND` and `MSP_VTXTABLE_POWERLEVEL` for details.", + "description": "Retrieves the current VTX (Video Transmitter) configuration and capabilities." + }, + "MSP_SET_VTX_CONFIG": { + "code": 89, + "mspv": 1, + "request": null, + "reply": null, + "variable_len": true, + "notes": "Requires dataSize >= 2. If no VTX device or device type is VTXDEV_UNKNOWN, fields are read and discarded. The first uint16 is interpreted as band/channel when value <= VTXCOMMON_MSP_BANDCHAN_CHKVAL, otherwise treated as a frequency value that is not applied by this path. Subsequent fields are applied only if present. If dataSize < 2 the command returns MSP_RESULT_ERROR.", + "description": "Sets VTX band/channel and related options. Fields are a progressive superset based on payload length.", + "variants": { + "payloadSize >= 14": { + "description": "Full payload (Betaflight 1.42+): includes explicit band/channel/frequency and capability counts.", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t", + "desc": "Encoded band/channel if <= `VTXCOMMON_MSP_BANDCHAN_CHKVAL`; otherwise frequency placeholder." + }, + { + "name": "power", + "ctype": "uint8_t" + }, + { + "name": "pitMode", + "ctype": "uint8_t" + }, + { + "name": "lowPowerDisarm", + "ctype": "uint8_t", + "enum": "vtxLowerPowerDisarm_e" + }, + { + "name": "pitModeFreq", + "ctype": "uint16_t" + }, + { + "name": "band", + "ctype": "uint8_t" + }, + { + "name": "channel", + "ctype": "uint8_t" + }, + { + "name": "frequency", + "ctype": "uint16_t" + }, + { + "name": "bandCount", + "ctype": "uint8_t", + "desc": "Read and ignored." + }, + { + "name": "channelCount", + "ctype": "uint8_t", + "desc": "Read and ignored." + }, + { + "name": "powerCount", + "ctype": "uint8_t", + "desc": "If 0 < value < current capability, caps `vtxDevice->capability.powerCount`." + } + ] + }, + "reply": null + }, + "payloadSize >= 11": { + "description": "Extends payload with explicit frequency.", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t" + }, + { + "name": "power", + "ctype": "uint8_t" + }, + { + "name": "pitMode", + "ctype": "uint8_t" + }, + { + "name": "lowPowerDisarm", + "ctype": "uint8_t", + "enum": "vtxLowerPowerDisarm_e" + }, + { + "name": "pitModeFreq", + "ctype": "uint16_t" + }, + { + "name": "band", + "ctype": "uint8_t" + }, + { + "name": "channel", + "ctype": "uint8_t" + }, + { + "name": "frequency", + "ctype": "uint16_t", + "desc": "Read and ignored by INAV." + } + ] + }, + "reply": null + }, + "payloadSize >= 9": { + "description": "Adds explicit band/channel overrides (API 1.42 extension).", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t" + }, + { + "name": "power", + "ctype": "uint8_t" + }, + { + "name": "pitMode", + "ctype": "uint8_t" + }, + { + "name": "lowPowerDisarm", + "ctype": "uint8_t", + "enum": "vtxLowerPowerDisarm_e" + }, + { + "name": "pitModeFreq", + "ctype": "uint16_t" + }, + { + "name": "band", + "ctype": "uint8_t", + "desc": "1..N; overrides band when present." + }, + { + "name": "channel", + "ctype": "uint8_t", + "desc": "1..8; overrides channel when present." + } + ] + }, + "reply": null + }, + "payloadSize >= 7": { + "description": "Adds pit-mode frequency placeholder.", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t" + }, + { + "name": "power", + "ctype": "uint8_t" + }, + { + "name": "pitMode", + "ctype": "uint8_t" + }, + { + "name": "lowPowerDisarm", + "ctype": "uint8_t", + "enum": "vtxLowerPowerDisarm_e" + }, + { + "name": "pitModeFreq", + "ctype": "uint16_t", + "desc": "Read and skipped." + } + ] + }, + "reply": null + }, + "payloadSize >= 5": { + "description": "Adds low-power disarm behaviour.", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t" + }, + { + "name": "power", + "ctype": "uint8_t" + }, + { + "name": "pitMode", + "ctype": "uint8_t" + }, + { + "name": "lowPowerDisarm", + "ctype": "uint8_t", + "enum": "vtxLowerPowerDisarm_e", + "desc": "0=Off, 1=Always, 2=Until first arm." + } + ] + }, + "reply": null + }, + "payloadSize >= 4": { + "description": "Adds power index and pit mode flag.", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t" + }, + { + "name": "power", + "ctype": "uint8_t" + }, + { + "name": "pitMode", + "ctype": "uint8_t" + } + ] + }, + "reply": null + }, + "payloadSize == 2": { + "description": "Minimum payload (band/channel encoded in 0..63).", + "request": { + "payload": [ + { + "name": "bandChanOrFreq", + "ctype": "uint16_t", + "desc": "If <= `VTXCOMMON_MSP_BANDCHAN_CHKVAL`, decoded as band/channel; otherwise treated as a frequency placeholder." + } + ] + }, + "reply": null } - ] + } }, - "reply": null, - "notes": "Expects 1 byte. Calls `mixerUpdateStateFlags()` for potential side effects related to presets.", - "description": "Sets the mixer type (Legacy, ignored by INAV)." - }, - "MSP_RX_CONFIG": { - "code": 44, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "serialRxProvider", - "ctype": "uint8_t", - "desc": "Enum `rxSerialReceiverType_e`. Serial RX provider (`rxConfig()->serialrx_provider`).", - "units": "Enum", - "enum": "rxSerialReceiverType_e" - }, - { - "name": "maxCheck", - "ctype": "uint16_t", - "desc": "Upper channel value threshold for stick commands (`rxConfig()->maxcheck`)", - "units": "PWM" - }, - { - "name": "midRc", - "ctype": "uint16_t", - "desc": "Center channel value (`PWM_RANGE_MIDDLE`, typically 1500)", - "units": "PWM" - }, - { - "name": "minCheck", - "ctype": "uint16_t", - "desc": "Lower channel value threshold for stick commands (`rxConfig()->mincheck`)", - "units": "PWM" - }, - { - "name": "spektrumSatBind", - "ctype": "uint8_t", - "desc": "Spektrum bind pulses (`rxConfig()->spektrum_sat_bind`). 0 if `USE_SPEKTRUM_BIND` disabled.", - "units": "Count/Flag" - }, - { - "name": "rxMinUsec", - "ctype": "uint16_t", - "desc": "Minimum expected pulse width (`rxConfig()->rx_min_usec`)", - "units": "PWM" - }, - { - "name": "rxMaxUsec", - "ctype": "uint16_t", - "desc": "Maximum expected pulse width (`rxConfig()->rx_max_usec`)", - "units": "PWM" - }, - { - "name": "bfCompatRcInterpolation", - "ctype": "uint8_t", - "desc": "BF compatibility. Always 0", - "value": 0 - }, - { - "name": "bfCompatRcInterpolationInt", - "ctype": "uint8_t", - "desc": "BF compatibility. Always 0", - "value": 0 - }, - { - "name": "bfCompatAirModeThreshold", - "ctype": "uint16_t", - "desc": "BF compatibility. Always 0", - "value": 0 - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Reserved/Padding. Always 0", - "value": 0 - }, - { - "name": "reserved2", - "ctype": "uint32_t", - "desc": "Reserved/Padding. Always 0", - "value": 0 - }, - { - "name": "reserved3", - "ctype": "uint8_t", - "desc": "Reserved/Padding. Always 0", - "value": 0 - }, - { - "name": "bfCompatFpvCamAngle", - "ctype": "uint8_t", - "desc": "BF compatibility. Always 0", - "value": 0 - }, - { - "name": "receiverType", - "ctype": "uint8_t", - "desc": "Enum `rxReceiverType_e` Receiver type (Parallel PWM, PPM, Serial) ('rxConfig()->receiverType')", - "units": "Enum", - "enum": "rxReceiverType_e" - } - ] - }, - "notes": "", - "description": "Retrieves receiver configuration settings. Some fields are Betaflight compatibility placeholders." - }, - "MSP_SET_RX_CONFIG": { - "code": 45, - "mspv": 1, - "request": { - "payload": [ - { - "name": "serialRxProvider", - "ctype": "uint8_t", - "desc": "Enum `rxSerialReceiverType_e`. Sets `rxConfigMutable()->serialrx_provider`.", - "units": "Enum", - "enum": "rxSerialReceiverType_e" - }, - { - "name": "maxCheck", - "ctype": "uint16_t", - "desc": "Sets `rxConfigMutable()->maxcheck`.", - "units": "PWM" - }, - { - "name": "midRc", - "ctype": "uint16_t", - "desc": "Ignored (`PWM_RANGE_MIDDLE` is used)", - "units": "PWM" - }, - { - "name": "minCheck", - "ctype": "uint16_t", - "desc": "Sets `rxConfigMutable()->mincheck`.", - "units": "PWM" - }, - { - "name": "spektrumSatBind", - "ctype": "uint8_t", - "desc": "Sets `rxConfigMutable()->spektrum_sat_bind` (if `USE_SPEKTRUM_BIND`).", - "units": "Count/Flag" - }, - { - "name": "rxMinUsec", - "ctype": "uint16_t", - "desc": "Sets `rxConfigMutable()->rx_min_usec`.", - "units": "PWM" - }, - { - "name": "rxMaxUsec", - "ctype": "uint16_t", - "desc": "Sets `rxConfigMutable()->rx_max_usec`.", - "units": "PWM" - }, - { - "name": "bfCompatRcInterpolation", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "bfCompatRcInterpolationInt", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "bfCompatAirModeThreshold", - "ctype": "uint16_t", - "desc": "Ignored" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "reserved2", - "ctype": "uint32_t", - "desc": "Ignored" - }, - { - "name": "reserved3", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "bfCompatFpvCamAngle", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "receiverType", - "ctype": "uint8_t", - "desc": "Enum `rxReceiverType_e` Sets `rxConfigMutable()->receiverType`.", - "units": "Enum", - "enum": "rxReceiverType_e" - } - ] - }, - "reply": null, - "notes": "Expects 24 bytes.", - "description": "Sets receiver configuration settings." - }, - "MSP_LED_COLORS": { - "code": 46, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "hue", - "ctype": "uint16_t", - "desc": "Hue value (0-359)", - "units": "" - }, - { - "name": "saturation", - "ctype": "uint8_t", - "desc": "Saturation value (0-255)", - "units": "" - }, - { - "name": "value", - "ctype": "uint8_t", - "desc": "Value/Brightness (0-255)", - "units": "" - } - ], - "repeating": "LED_CONFIGURABLE_COLOR_COUNT" - }, - "notes": "Only available if `USE_LED_STRIP` is defined.", - "description": "Retrieves the HSV color definitions for configurable LED colors." - }, - "MSP_SET_LED_COLORS": { - "code": 47, - "mspv": 1, - "request": { - "payload": [ - { - "name": "hue", - "ctype": "uint16_t", - "desc": "Hue value (0-359)", - "units": "" - }, - { - "name": "saturation", - "ctype": "uint8_t", - "desc": "Saturation value (0-255)", - "units": "" - }, - { - "name": "value", - "ctype": "uint8_t", - "desc": "Value/Brightness (0-255)", - "units": "" - } - ], - "repeating": "LED_CONFIGURABLE_COLOR_COUNT" - }, - "reply": null, - "notes": "Only available if `USE_LED_STRIP` is defined. Expects `LED_CONFIGURABLE_COLOR_COUNT * 4` bytes.", - "description": "Sets the HSV color definitions for configurable LED colors." - }, - "MSP_LED_STRIP_CONFIG": { - "code": 48, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "legacyLedConfig", - "ctype": "uint32_t", - "desc": "Packed LED configuration (position, function, overlay, color, direction, params). See C code for bit packing details", - "units": "" - } - ], - "repeating": "LED_MAX_STRIP_LENGTH" - }, - "variable_len": "LED_MAX_STRIP_LENGTH", - "notes": "Only available if `USE_LED_STRIP` is defined. Superseded by `MSP2_INAV_LED_STRIP_CONFIG_EX` which uses a clearer struct.", - "description": "Retrieves the configuration for each LED on the strip (legacy packed format)." - }, - "MSP_SET_LED_STRIP_CONFIG": { - "code": 49, - "mspv": 1, - "request": { - "payload": [ - { - "name": "ledIndex", - "ctype": "uint8_t", - "desc": "Index of the LED to configure (0 to `LED_MAX_STRIP_LENGTH - 1`)", - "units": "" - }, - { - "name": "legacyLedConfig", - "ctype": "uint32_t", - "desc": "Packed LED configuration to set", - "units": "" - } - ] - }, - "reply": null, - "notes": "Only available if `USE_LED_STRIP` is defined. Expects 5 bytes. Calls `reevaluateLedConfig()`. Superseded by `MSP2_INAV_SET_LED_STRIP_CONFIG_EX`.", - "description": "Sets the configuration for a single LED on the strip using the legacy packed format." - }, - "MSP_RSSI_CONFIG": { - "code": 50, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "rssiChannel", - "ctype": "uint8_t", - "desc": "AUX channel index (1-based) used for RSSI, or 0 if disabled (`rxConfig()->rssi_channel`)", - "units": "" - } - ] - }, - "notes": "", - "description": "Retrieves the channel used for analog RSSI input." - }, - "MSP_SET_RSSI_CONFIG": { - "code": 51, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rssiChannel", - "ctype": "uint8_t", - "desc": "AUX channel index (1-based) to use for RSSI, or 0 to disable", - "units": "" - } - ] - }, - "reply": null, - "notes": "Expects 1 byte. Input value is constrained 0 to `MAX_SUPPORTED_RC_CHANNEL_COUNT`. Updates the effective RSSI source.", - "description": "Sets the channel used for analog RSSI input." - }, - "MSP_ADJUSTMENT_RANGES": { - "code": 52, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "adjustmentIndex", - "ctype": "uint8_t", - "desc": "Index of the adjustment slot (0 to `MAX_SIMULTANEOUS_ADJUSTMENT_COUNT - 1`)", - "units": "" - }, - { - "name": "auxChannelIndex", - "ctype": "uint8_t", - "desc": "0-based index of the AUX channel controlling the adjustment value", - "units": "" - }, - { - "name": "rangeStartStep", - "ctype": "uint8_t", - "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", - "units": "step" - }, - { - "name": "rangeEndStep", - "ctype": "uint8_t", - "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", - "units": "step" - }, - { - "name": "adjustmentFunction", - "ctype": "uint8_t", - "desc": "Function/parameter being adjusted (see `adjustmentFunction_e`).", - "units": "", - "enum": "adjustmentFunction_e" - }, - { - "name": "auxSwitchChannelIndex", - "ctype": "uint8_t", - "desc": "0-based index of the AUX channel acting as an enable switch (or 0 if always enabled)", - "units": "" - } - ], - "repeating": "MAX_ADJUSTMENT_RANGE_COUNT" - }, - "notes": "See `adjustmentRange_t`.", - "description": "Returns all defined RC adjustment ranges (tuning via aux channels)." - }, - "MSP_SET_ADJUSTMENT_RANGE": { - "code": 53, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rangeIndex", - "ctype": "uint8_t", - "desc": "Index of the adjustment range to set (0 to `MAX_ADJUSTMENT_RANGE_COUNT - 1`)", - "units": "" - }, - { - "name": "adjustmentIndex", - "ctype": "uint8_t", - "desc": "Adjustment slot index (0 to `MAX_SIMULTANEOUS_ADJUSTMENT_COUNT - 1`)", - "units": "" - }, - { - "name": "auxChannelIndex", - "ctype": "uint8_t", - "desc": "0-based index of the control AUX channel", - "units": "" - }, - { - "name": "rangeStartStep", - "ctype": "uint8_t", - "desc": "Start step (0-48). Each step is 25 PWM units; 0 is <=900 and 48 is >=2100.", - "units": "step" - }, - { - "name": "rangeEndStep", - "ctype": "uint8_t", - "desc": "End step (0-48). Uses the same 25-PWM step mapping as rangeStartStep.", - "units": "step" - }, - { - "name": "adjustmentFunction", - "ctype": "uint8_t", - "desc": "Function/parameter being adjusted.", - "units": "", - "enum": "adjustmentFunction_e" - }, - { - "name": "auxSwitchChannelIndex", - "ctype": "uint8_t", - "desc": "0-based index of the enable switch AUX channel (or 0)", - "units": "" - } - ] - }, - "reply": null, - "notes": "Expects 7 bytes. Returns error if `rangeIndex` or `adjustmentIndex` is invalid.", - "description": "Sets a single RC adjustment range configuration by its index." - }, - "MSP_CF_SERIAL_CONFIG": { - "code": 54, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`. Use `MSP2_COMMON_SERIAL_CONFIG`.", - "description": "Deprecated command to get serial port configuration." - }, - "MSP_SET_CF_SERIAL_CONFIG": { - "code": 55, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`. Use `MSP2_COMMON_SET_SERIAL_CONFIG`.", - "description": "Deprecated command to set serial port configuration." - }, - "MSP_VOLTAGE_METER_CONFIG": { - "code": 56, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "vbatScale", - "ctype": "uint8_t", - "desc": "Voltage sensor scale factor / 10 (`batteryMetersConfig()->voltage.scale / 10`). 0 if `USE_ADC` disabled", - "units": "Scale / 10" - }, - { - "name": "vbatMinCell", - "ctype": "uint8_t", - "desc": "Minimum cell voltage / 10 (`currentBatteryProfile->voltage.cellMin / 10`). 0 if `USE_ADC` disabled", - "units": "0.1V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint8_t", - "desc": "Maximum cell voltage / 10 (`currentBatteryProfile->voltage.cellMax / 10`). 0 if `USE_ADC` disabled", - "units": "0.1V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint8_t", - "desc": "Warning cell voltage / 10 (`currentBatteryProfile->voltage.cellWarning / 10`). 0 if `USE_ADC` disabled", - "units": "0.1V" - } - ] - }, - "notes": "Superseded by `MSP2_INAV_BATTERY_CONFIG`.", - "description": "Retrieves legacy voltage meter configuration (scaled values)." - }, - "MSP_SET_VOLTAGE_METER_CONFIG": { - "code": 57, - "mspv": 1, - "request": { - "payload": [ - { - "name": "vbatScale", - "ctype": "uint8_t", - "desc": "Sets `batteryMetersConfigMutable()->voltage.scale = value * 10` (if `USE_ADC`)", - "units": "Scale / 10" - }, - { - "name": "vbatMinCell", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin = value * 10` (if `USE_ADC`)", - "units": "0.1V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax = value * 10` (if `USE_ADC`)", - "units": "0.1V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning = value * 10` (if `USE_ADC`)", - "units": "0.1V" - } - ] - }, - "reply": null, - "notes": "Expects 4 bytes. Superseded by `MSP2_INAV_SET_BATTERY_CONFIG`.", - "description": "Sets legacy voltage meter configuration (scaled values)." - }, - "MSP_SONAR_ALTITUDE": { - "code": 58, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "rangefinderAltitude", - "ctype": "int32_t", - "desc": "Latest altitude reading from the rangefinder (`rangefinderGetLatestAltitude()`). 0 if `USE_RANGEFINDER` disabled or no reading.", - "units": "cm" - } - ] - }, - "notes": "", - "description": "Retrieves the altitude measured by the primary rangefinder (sonar or lidar)." - }, - "MSP_RX_MAP": { - "code": 64, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "rcMap", - "desc": "Array defining the mapping from input channel index to logical function (Roll, Pitch, Yaw, Throttle, Aux1...)", - "ctype": "uint8_t", - "array": true, - "array_size": 4, - "array_size_define": "MAX_MAPPABLE_RX_INPUTS", - "units": "" - } - ] - }, - "notes": "`MAX_MAPPABLE_RX_INPUTS` is currently 4 (Roll, Pitch, Yaw, Throttle).", - "description": "Retrieves the RC channel mapping array (AETR, etc.)." - }, - "MSP_SET_RX_MAP": { - "code": 65, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rcMap", - "desc": "Array defining the new channel mapping", - "ctype": "uint8_t", - "array": true, - "array_size": 4, - "array_size_define": "MAX_MAPPABLE_RX_INPUTS", - "units": "" - } - ] - }, - "reply": null, - "notes": "Expects `MAX_MAPPABLE_RX_INPUTS` bytes (currently 4).", - "description": "Sets the RC channel mapping array." - }, - "MSP_REBOOT": { - "code": 68, - "mspv": 1, - "request": null, - "reply": null, - "notes": "The FC sends an ACK *before* rebooting. The `mspPostProcessFn` is set to `mspRebootFn` to perform the reboot after the reply is sent. Will fail if the craft is armed.", - "description": "Commands the flight controller to reboot." - }, - "MSP_DATAFLASH_SUMMARY": { - "code": 70, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "flashReady", - "ctype": "uint8_t", - "desc": "Boolean: 1 if flash chip is ready, 0 otherwise. (`flashIsReady()`). 0 if `USE_FLASHFS` disabled", - "units": "" - }, - { - "name": "sectorCount", - "ctype": "uint32_t", - "desc": "Total number of sectors on the flash chip (`geometry->sectors`). 0 if `USE_FLASHFS` disabled", - "units": "" - }, - { - "name": "totalSize", - "ctype": "uint32_t", - "desc": "Total size of the flash chip in bytes (`geometry->totalSize`). 0 if `USE_FLASHFS` disabled", - "units": "" - }, - { - "name": "usedSize", - "ctype": "uint32_t", - "desc": "Currently used size in bytes (FlashFS offset) (`flashfsGetOffset()`). 0 if `USE_FLASHFS` disabled", - "units": "" - } - ] - }, - "notes": "Requires `USE_FLASHFS`.", - "description": "Retrieves summary information about the onboard dataflash chip (if present and used for Blackbox via FlashFS)." - }, - "MSP_DATAFLASH_READ": { - "code": 71, - "mspv": 1, - "request": { - "payload": [ - { - "name": "address", - "ctype": "uint32_t", - "desc": "Starting address to read from within the FlashFS volume", - "units": "" - }, - { - "name": "size", - "ctype": "uint16_t", - "desc": "(Optional) Number of bytes to read. Defaults to 128 if not provided", - "units": "", - "optional": true - } - ] - }, - "reply": { - "payload": [ - { - "name": "address", - "ctype": "uint32_t", - "desc": "The starting address from which data was actually read", - "units": "" - }, - { - "name": "data", - "desc": "The data read from flash. Length is MIN(requested size, remaining buffer space, remaining flashfs data)", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "Requires `USE_FLASHFS`. Read length may be truncated by buffer size or end of flashfs volume.", - "description": "Reads a block of data from the onboard dataflash (FlashFS)." - }, - "MSP_DATAFLASH_ERASE": { - "code": 72, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Requires `USE_FLASHFS`. This is a potentially long operation. Use with caution.", - "description": "Erases the entire onboard dataflash chip (FlashFS volume)." - }, - "MSP_LOOP_TIME": { - "code": 73, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "looptime", - "ctype": "uint16_t", - "desc": "Configured loop time (`gyroConfig()->looptime`)", - "units": "PWM" - } - ] - }, - "notes": "This is the *configured* target loop time, not necessarily the *actual* measured cycle time (see `MSP_STATUS`).", - "description": "Retrieves the configured loop time (PID loop frequency denominator)." - }, - "MSP_SET_LOOP_TIME": { - "code": 74, - "mspv": 1, - "request": { - "payload": [ - { - "name": "looptime", - "ctype": "uint16_t", - "desc": "New loop time to set (`gyroConfigMutable()->looptime`)", - "units": "PWM" - } - ] - }, - "reply": null, - "notes": "Expects 2 bytes.", - "description": "Sets the configured loop time." - }, - "MSP_FAILSAFE_CONFIG": { - "code": 75, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "failsafeDelay", - "ctype": "uint8_t", - "desc": "Delay before failsafe stage 1 activates (`failsafeConfig()->failsafe_delay`)", - "units": "0.1s" - }, - { - "name": "failsafeOffDelay", - "ctype": "uint8_t", - "desc": "Delay after signal recovery before returning control (`failsafeConfig()->failsafe_off_delay`)", - "units": "0.1s" - }, - { - "name": "failsafeThrottle", - "ctype": "uint16_t", - "desc": "Throttle level during failsafe stage 2 (`currentBatteryProfile->failsafe_throttle`)", - "units": "PWM" - }, - { - "name": "legacyKillSwitch", - "ctype": "uint8_t", - "desc": "Legacy flag, always 0", - "value": 0 - }, - { - "name": "failsafeThrottleLowDelay", - "ctype": "uint16_t", - "desc": "Delay for throttle-based failsafe detection (`failsafeConfig()->failsafe_throttle_low_delay`). Units of 0.1 seconds.", - "units": "0.1s" - }, - { - "name": "failsafeProcedure", - "ctype": "uint8_t", - "desc": "Enum `failsafeProcedure_e` Failsafe procedure (Drop, RTH, Land, etc.) ('failsafeConfig()->failsafe_procedure')", - "units": "Enum", - "enum": "failsafeProcedure_e" - }, - { - "name": "failsafeRecoveryDelay", - "ctype": "uint8_t", - "desc": "Delay after RTH finishes before attempting recovery (`failsafeConfig()->failsafe_recovery_delay`)", - "units": "0.1s" - }, - { - "name": "failsafeFWRollAngle", - "ctype": "int16_t", - "desc": "Fixed-wing failsafe roll angle (`failsafeConfig()->failsafe_fw_roll_angle`). Signed deci-degrees.", - "units": "deci-degrees" - }, - { - "name": "failsafeFWPitchAngle", - "ctype": "int16_t", - "desc": "Fixed-wing failsafe pitch angle (`failsafeConfig()->failsafe_fw_pitch_angle`). Signed deci-degrees.", - "units": "deci-degrees" - }, - { - "name": "failsafeFWYawRate", - "ctype": "int16_t", - "desc": "Fixed-wing failsafe yaw rate (`failsafeConfig()->failsafe_fw_yaw_rate`). Signed degrees per second.", - "units": "deg/s" - }, - { - "name": "failsafeStickThreshold", - "ctype": "uint16_t", - "desc": "Stick movement threshold to exit failsafe (`failsafeConfig()->failsafe_stick_motion_threshold`)", - "units": "PWM units" - }, - { - "name": "failsafeMinDistance", - "ctype": "uint16_t", - "desc": "Minimum distance from home for RTH failsafe (`failsafeConfig()->failsafe_min_distance`). Units of centimeters.", - "units": "cm" - }, - { - "name": "failsafeMinDistanceProc", - "ctype": "uint8_t", - "desc": "Enum `failsafeProcedure_e` Failsafe procedure if below min distance ('failsafeConfig()->failsafe_min_distance_procedure')", - "units": "Enum", - "enum": "failsafeProcedure_e" - } - ] - }, - "notes": "", - "description": "Retrieves the failsafe configuration settings." - }, - "MSP_SET_FAILSAFE_CONFIG": { - "code": 76, - "mspv": 1, - "request": { - "payload": [ - { - "name": "failsafeDelay", - "ctype": "uint8_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_delay`.", - "units": "0.1s" - }, - { - "name": "failsafeOffDelay", - "ctype": "uint8_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_off_delay`.", - "units": "0.1s" - }, - { - "name": "failsafeThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->failsafe_throttle`.", - "units": "PWM" - }, - { - "name": "legacyKillSwitch", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "failsafeThrottleLowDelay", - "ctype": "uint16_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_throttle_low_delay`. Units of 0.1 seconds.", - "units": "0.1s" - }, - { - "name": "failsafeProcedure", - "ctype": "uint8_t", - "desc": "Enum `failsafeProcedure_e`. Sets `failsafeConfigMutable()->failsafe_procedure`.", - "units": "Enum", - "enum": "failsafeProcedure_e" - }, - { - "name": "failsafeRecoveryDelay", - "ctype": "uint8_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_recovery_delay`.", - "units": "0.1s" - }, - { - "name": "failsafeFWRollAngle", - "ctype": "int16_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_fw_roll_angle`. Signed deci-degrees.", - "units": "deci-degrees" - }, - { - "name": "failsafeFWPitchAngle", - "ctype": "int16_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_fw_pitch_angle`. Signed deci-degrees.", - "units": "deci-degrees" - }, - { - "name": "failsafeFWYawRate", - "ctype": "int16_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_fw_yaw_rate`. Signed degrees per second.", - "units": "deg/s" - }, - { - "name": "failsafeStickThreshold", - "ctype": "uint16_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_stick_motion_threshold`.", - "units": "PWM units" - }, - { - "name": "failsafeMinDistance", - "ctype": "uint16_t", - "desc": "Sets `failsafeConfigMutable()->failsafe_min_distance`. Units of centimeters.", - "units": "cm" - }, - { - "name": "failsafeMinDistanceProc", - "ctype": "uint8_t", - "desc": "Enum `failsafeProcedure_e`. Sets `failsafeConfigMutable()->failsafe_min_distance_procedure`.", - "units": "Enum", - "enum": "failsafeProcedure_e" - } - ] - }, - "reply": null, - "notes": "Expects 20 bytes.", - "description": "Sets the failsafe configuration settings." - }, - "MSP_SDCARD_SUMMARY": { - "code": 79, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "sdCardSupported", - "ctype": "uint8_t", - "desc": "Bitmask: Bit 0 = 1 if SD card support compiled in (`USE_SDCARD`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "sdCardState", - "ctype": "uint8_t", - "desc": "Enum (`mspSDCardState_e`): Current state (Not Present, Fatal, Card Init, FS Init, Ready). 0 if `USE_SDCARD` disabled", - "units": "", - "enum": "mspSDCardState_e" - }, - { - "name": "fsError", - "ctype": "uint8_t", - "desc": "Last filesystem error code (`afatfs_getLastError()`). 0 if `USE_SDCARD` disabled", - "units": "" - }, - { - "name": "freeSpaceKB", - "ctype": "uint32_t", - "desc": "Free space in KiB (`afatfs_getContiguousFreeSpace() / 1024`). 0 if `USE_SDCARD` disabled", - "units": "" - }, - { - "name": "totalSpaceKB", - "ctype": "uint32_t", - "desc": "Total space in KiB (`sdcard_getMetadata()->numBlocks / 2`). 0 if `USE_SDCARD` disabled", - "units": "" - } - ] - }, - "notes": "Requires `USE_SDCARD` and `USE_ASYNCFATFS`.", - "description": "Retrieves summary information about the SD card status and filesystem." - }, - "MSP_BLACKBOX_CONFIG": { - "code": 80, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "blackboxDevice", - "ctype": "uint8_t", - "desc": "Always 0 (API no longer supported)", - "units": "", - "value": 0 - }, - { - "name": "blackboxRateNum", - "ctype": "uint8_t", - "desc": "Always 0", - "units": "", - "value": 0 - }, - { - "name": "blackboxRateDenom", - "ctype": "uint8_t", - "desc": "Always 0", - "units": "", - "value": 0 - }, - { - "name": "blackboxPDenom", - "ctype": "uint8_t", - "desc": "Always 0", - "units": "", - "value": 0 - } - ] - }, - "notes": "Returns fixed zero values. Use `MSP2_BLACKBOX_CONFIG`.", - "description": "Legacy command to retrieve Blackbox configuration. Superseded by `MSP2_BLACKBOX_CONFIG`." - }, - "MSP_SET_BLACKBOX_CONFIG": { - "code": 81, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in `fc_msp.c`. Use `MSP2_SET_BLACKBOX_CONFIG`.", - "description": "Legacy command to set Blackbox configuration. Superseded by `MSP2_SET_BLACKBOX_CONFIG`." - }, - "MSP_TRANSPONDER_CONFIG": { - "code": 82, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`.", - "description": "Get VTX Transponder settings (likely specific to RaceFlight/Betaflight, not standard INAV VTX)." - }, - "MSP_SET_TRANSPONDER_CONFIG": { - "code": 83, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`.", - "description": "Set VTX Transponder settings." - }, - "MSP_OSD_CONFIG": { - "code": 84, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "osdDriverType", - "ctype": "uint8_t", - "desc": "Enum `osdDriver_e`: `OSD_DRIVER_MAX7456` if `USE_OSD`, else `OSD_DRIVER_NONE`.", - "units": "Enum", - "enum": "osdDriver_e" - }, - { - "name": "videoSystem", - "ctype": "uint8_t", - "desc": "Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`). Sent even if OSD disabled", - "units": "Enum", - "enum": "videoSystem_e" - }, - { - "name": "units", - "ctype": "uint8_t", - "desc": "Enum `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`). Sent even if OSD disabled", - "units": "Enum", - "enum": "osd_unit_e" - }, - { - "name": "rssiAlarm", - "ctype": "uint8_t", - "desc": "RSSI alarm threshold (`osdConfig()->rssi_alarm`). Sent even if OSD disabled", - "units": "%" - }, - { - "name": "capAlarm", - "ctype": "uint16_t", - "desc": "Capacity alarm threshold (`currentBatteryProfile->capacity.warning`). Truncated to 16 bits. Sent even if OSD disabled.", - "units": "mAh/mWh" - }, - { - "name": "timerAlarm", - "ctype": "uint16_t", - "desc": "Timer alarm threshold in minutes (`osdConfig()->time_alarm`). Sent even if OSD disabled.", - "units": "minutes" - }, - { - "name": "altAlarm", - "ctype": "uint16_t", - "desc": "Altitude alarm threshold (`osdConfig()->alt_alarm`). Sent even if OSD disabled", - "units": "meters" - }, - { - "name": "distAlarm", - "ctype": "uint16_t", - "desc": "Distance alarm threshold (`osdConfig()->dist_alarm`). Sent even if OSD disabled", - "units": "meters" - }, - { - "name": "negAltAlarm", - "ctype": "uint16_t", - "desc": "Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`). Sent even if OSD disabled", - "units": "meters" - }, - { - "name": "itemPositions", - "desc": "Packed X/Y position for each OSD item on screen 0 (`osdLayoutsConfig()->item_pos[0][i]`). Sent even if OSD disabled", - "ctype": "uint16_t", - "array": true, - "array_size": 0, - "array_size_define": "OSD_ITEM_COUNT", - "units": "packed" - } - ] - }, - "variable_len": true, - "notes": "1 byte if `USE_OSD` disabled; full payload (1 + fields + 2*OSD_ITEM_COUNT bytes) otherwise.", - "description": "Retrieves OSD configuration settings and layout for screen 0. Coordinates are packed as `(Y << 8) | X`. When `USE_OSD` is not compiled in, only `osdDriverType` = `OSD_DRIVER_NONE` is returned." - }, - "MSP_SET_OSD_CONFIG": { - "code": 85, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Requires `USE_OSD`. Distinguishes formats based on the first byte. Format 1 requires at least 10 bytes. Format 2 requires 3 bytes. Triggers an OSD redraw. See `MSP2_INAV_OSD_SET_*` for more advanced control.", - "description": "Sets OSD configuration or a single item's position on screen 0.", - "variants": { - "dataSize >= 10": { - "description": "dataSize >= 10", - "request": { - "payload": [ - { - "name": "selector", - "ctype": "uint8_t", - "desc": "Must be 0xFF (-1) to indicate a configuration update.", - "value": 255 - }, - { - "name": "videoSystem", - "ctype": "uint8_t", - "desc": "Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`).", - "units": "Enum", - "enum": "videoSystem_e" - }, - { - "name": "units", - "ctype": "uint8_t", - "desc": "Enum `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`).", - "units": "Enum", - "enum": "osd_unit_e" - }, - { - "name": "rssiAlarm", - "ctype": "uint8_t", - "desc": "RSSI alarm threshold (`osdConfig()->rssi_alarm`).", - "units": "%" - }, - { - "name": "capAlarm", - "ctype": "uint16_t", - "desc": "Capacity alarm threshold (`currentBatteryProfile->capacity.warning`). Truncated to 16 bits.", - "units": "mAh/mWh" - }, - { - "name": "timerAlarm", - "ctype": "uint16_t", - "desc": "Timer alarm threshold in minutes (`osdConfig()->time_alarm`).", - "units": "minutes" - }, - { - "name": "altAlarm", - "ctype": "uint16_t", - "desc": "Altitude alarm threshold (`osdConfig()->alt_alarm`).", - "units": "meters" - }, - { - "name": "distAlarm", - "ctype": "uint16_t", - "desc": "Distance alarm threshold (`osdConfig()->dist_alarm`). Optional trailing field.", - "units": "meters", - "optional": true - }, - { - "name": "negAltAlarm", - "ctype": "uint16_t", - "desc": "Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`). Optional trailing field.", - "units": "meters", - "optional": true - } - ] - }, - "reply": null + "MSP_ADVANCED_CONFIG": { + "code": 90, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "gyroSyncDenom", + "ctype": "uint8_t", + "desc": "Always 1 (BF compatibility)", + "units": "", + "value": 1 + }, + { + "name": "pidProcessDenom", + "ctype": "uint8_t", + "desc": "Always 1 (BF compatibility)", + "units": "", + "value": 1 + }, + { + "name": "useUnsyncedPwm", + "ctype": "uint8_t", + "desc": "Always 1 (BF compatibility, INAV uses async PWM based on protocol)", + "units": "", + "value": 1 + }, + { + "name": "motorPwmProtocol", + "ctype": "uint8_t", + "desc": "Motor PWM protocol type (`motorConfig()->motorPwmProtocol`).", + "units": "Enum", + "enum": "motorPwmProtocolTypes_e" + }, + { + "name": "motorPwmRate", + "ctype": "uint16_t", + "desc": "Motor PWM rate (if applicable) (`motorConfig()->motorPwmRate`).", + "units": "Hz" + }, + { + "name": "servoPwmRate", + "ctype": "uint16_t", + "desc": "Servo PWM rate (`servoConfig()->servoPwmRate`).", + "units": "Hz" + }, + { + "name": "legacyGyroSync", + "ctype": "uint8_t", + "desc": "Always 0 (BF compatibility)", + "units": "", + "value": 0 + } + ] }, - "dataSize == 3": { - "description": "Single item position update", + "notes": "", + "description": "Retrieves advanced hardware-related configuration (PWM protocols, rates). Some fields are BF compatibility placeholders." + }, + "MSP_SET_ADVANCED_CONFIG": { + "code": 91, + "mspv": 1, "request": { "payload": [ { - "name": "itemIndex", + "name": "gyroSyncDenom", "ctype": "uint8_t", - "desc": "Index of the OSD item to update (0 to `OSD_ITEM_COUNT - 1`).", - "units": "Index" + "desc": "Ignored (legacy Betaflight field).", + "units": "" }, { - "name": "itemPosition", + "name": "pidProcessDenom", + "ctype": "uint8_t", + "desc": "Ignored (legacy Betaflight field).", + "units": "" + }, + { + "name": "useUnsyncedPwm", + "ctype": "uint8_t", + "desc": "Ignored (legacy Betaflight field).", + "units": "" + }, + { + "name": "motorPwmProtocol", + "ctype": "uint8_t", + "desc": "Sets `motorConfigMutable()->motorPwmProtocol`.", + "units": "Enum", + "enum": "motorPwmProtocolTypes_e" + }, + { + "name": "motorPwmRate", "ctype": "uint16_t", - "desc": "Packed X/Y position (`(Y << 8) | X`) for the specified item.", - "units": "packed" + "desc": "Sets `motorConfigMutable()->motorPwmRate`.", + "units": "Hz" + }, + { + "name": "servoPwmRate", + "ctype": "uint16_t", + "desc": "Sets `servoConfigMutable()->servoPwmRate`.", + "units": "Hz" + }, + { + "name": "legacyGyroSync", + "ctype": "uint8_t", + "desc": "Ignored (legacy Betaflight field).", + "units": "" } ] }, - "reply": null - } - } - }, - "MSP_OSD_CHAR_READ": { - "code": 86, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`. Requires direct hardware access, typically done via DisplayPort.", - "description": "Reads character data from the OSD font memory." - }, - "MSP_OSD_CHAR_WRITE": { - "code": 87, - "mspv": 1, - "request": null, - "reply": null, - "variable_len": true, - "notes": "Requires `USE_OSD`. Minimum payload is `OSD_CHAR_VISIBLE_BYTES + 1` (8-bit address + 54 bytes). Payload size determines the address width and whether the extra metadata bytes are present. Writes characters via `displayWriteFontCharacter()`.", - "description": "Writes character data to the OSD font memory.", - "variants": { - "payloadSize >= OSD_CHAR_BYTES + 2 (>=66 bytes)": { - "description": "16-bit character index with full 64-byte payload (visible + metadata).", - "request": { - "payload": [ - { - "name": "address", - "ctype": "uint16_t", - "desc": "Character slot index (0-1023)." - }, - { - "name": "charData", - "desc": "All 64 bytes, including driver metadata.", - "ctype": "uint8_t", - "array": true, - "array_size": 64, - "array_size_define": "OSD_CHAR_BYTES" - } - ] - }, - "reply": null + "reply": null, + "notes": "Expects 9 bytes.", + "description": "Sets advanced hardware-related configuration (PWM protocols, rates)." + }, + "MSP_FILTER_CONFIG": { + "code": 92, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "gyroMainLpfHz", + "ctype": "uint8_t", + "desc": "Gyro main low-pass filter cutoff frequency (`gyroConfig()->gyro_main_lpf_hz`)", + "units": "Hz" + }, + { + "name": "dtermLpfHz", + "ctype": "uint16_t", + "desc": "D-term low-pass filter cutoff frequency (`pidProfile()->dterm_lpf_hz`)", + "units": "Hz" + }, + { + "name": "yawLpfHz", + "ctype": "uint16_t", + "desc": "Yaw low-pass filter cutoff frequency (`pidProfile()->yaw_lpf_hz`)", + "units": "Hz" + }, + { + "name": "legacyGyroNotchHz", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "legacyGyroNotchCutoff", + "ctype": "uint16_t", + "desc": "Always 1 (Legacy)", + "value": 1 + }, + { + "name": "bfCompatDtermNotchHz", + "ctype": "uint16_t", + "desc": "Always 0 (BF compatibility)", + "value": 0 + }, + { + "name": "bfCompatDtermNotchCutoff", + "ctype": "uint16_t", + "desc": "Always 1 (BF compatibility)", + "value": 1 + }, + { + "name": "bfCompatGyroNotch2Hz", + "ctype": "uint16_t", + "desc": "Always 0 (BF compatibility)", + "value": 0 + }, + { + "name": "bfCompatGyroNotch2Cutoff", + "ctype": "uint16_t", + "desc": "Always 1 (BF compatibility)", + "value": 1 + }, + { + "name": "accNotchHz", + "ctype": "uint16_t", + "desc": "Accelerometer notch filter center frequency (`accelerometerConfig()->acc_notch_hz`)", + "units": "Hz" + }, + { + "name": "accNotchCutoff", + "ctype": "uint16_t", + "desc": "Accelerometer notch filter cutoff frequency (`accelerometerConfig()->acc_notch_cutoff`)", + "units": "Hz" + }, + { + "name": "legacyGyroStage2LpfHz", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + } + ] }, - "payloadSize == OSD_CHAR_BYTES + 1 (65 bytes)": { - "description": "8-bit character index with full 64-byte payload.", - "request": { - "payload": [ - { - "name": "address", - "ctype": "uint8_t", - "desc": "Character slot index (0-255)." - }, - { - "name": "charData", - "desc": "All 64 bytes, including driver metadata.", - "ctype": "uint8_t", - "array": true, - "array_size": 64, - "array_size_define": "OSD_CHAR_BYTES" - } - ] - }, - "reply": null + "notes": "", + "description": "Retrieves filter configuration settings (Gyro, D-term, Yaw, Accel). Some fields are BF compatibility placeholders or legacy." + }, + "MSP_SET_FILTER_CONFIG": { + "code": 93, + "mspv": 1, + "request": { + "payload": [ + { + "name": "gyroMainLpfHz", + "ctype": "uint8_t", + "desc": "Sets `gyroConfigMutable()->gyro_main_lpf_hz`. (Size >= 5)", + "units": "Hz" + }, + { + "name": "dtermLpfHz", + "ctype": "uint16_t", + "desc": "Sets `pidProfileMutable()->dterm_lpf_hz` (constrained 0-500). (Size >= 5)", + "units": "Hz" + }, + { + "name": "yawLpfHz", + "ctype": "uint16_t", + "desc": "Sets `pidProfileMutable()->yaw_lpf_hz` (constrained 0-255). (Size >= 5)", + "units": "Hz" + }, + { + "name": "legacyGyroNotchHz", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 9)" + }, + { + "name": "legacyGyroNotchCutoff", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 9)" + }, + { + "name": "bfCompatDtermNotchHz", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 13)" + }, + { + "name": "bfCompatDtermNotchCutoff", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 13)" + }, + { + "name": "bfCompatGyroNotch2Hz", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 17)" + }, + { + "name": "bfCompatGyroNotch2Cutoff", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 17)" + }, + { + "name": "accNotchHz", + "ctype": "uint16_t", + "desc": "Sets `accelerometerConfigMutable()->acc_notch_hz` (constrained 0-255). (Size >= 21)", + "units": "Hz" + }, + { + "name": "accNotchCutoff", + "ctype": "uint16_t", + "desc": "Sets `accelerometerConfigMutable()->acc_notch_cutoff` (constrained 1-255). (Size >= 21)", + "units": "Hz" + }, + { + "name": "legacyGyroStage2LpfHz", + "ctype": "uint16_t", + "desc": "Ignored. (Size >= 22)" + } + ] }, - "payloadSize == OSD_CHAR_VISIBLE_BYTES + 2 (56 bytes)": { - "description": "16-bit character index with only the 54 visible bytes.", - "request": { - "payload": [ - { - "name": "address", - "ctype": "uint16_t", - "desc": "Character slot index (0-1023)." - }, - { - "name": "charData", - "desc": "Visible pixel data only (no metadata).", - "ctype": "uint8_t", - "array": true, - "array_size": 54, - "array_size_define": "OSD_CHAR_VISIBLE_BYTES" - } - ] - }, - "reply": null + "reply": null, + "notes": "Requires at least 22 bytes; intermediate length checks enforce legacy Betaflight frame layout and call `pidInitFilters()` once the D-term notch placeholders are consumed.", + "description": "Sets filter configuration settings. Handles different payload lengths for backward compatibility." + }, + "MSP_PID_ADVANCED": { + "code": 94, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "legacyRollPitchItermIgnore", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "legacyYawItermIgnore", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "legacyYawPLimit", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "bfCompatDeltaMethod", + "ctype": "uint8_t", + "desc": "Always 0 (BF compatibility)", + "value": 0 + }, + { + "name": "bfCompatVbatPidComp", + "ctype": "uint8_t", + "desc": "Always 0 (BF compatibility)", + "value": 0 + }, + { + "name": "bfCompatSetpointRelaxRatio", + "ctype": "uint8_t", + "desc": "Always 0 (BF compatibility)", + "value": 0 + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Always 0", + "value": 0 + }, + { + "name": "legacyPidSumLimit", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "bfCompatItermThrottleGain", + "ctype": "uint8_t", + "desc": "Always 0 (BF compatibility)", + "value": 0 + }, + { + "name": "accelLimitRollPitch", + "ctype": "uint16_t", + "desc": "Axis acceleration limit for Roll/Pitch / 10 (`pidProfile()->axisAccelerationLimitRollPitch / 10`)", + "units": "dps / 10" + }, + { + "name": "accelLimitYaw", + "ctype": "uint16_t", + "desc": "Axis acceleration limit for Yaw / 10 (`pidProfile()->axisAccelerationLimitYaw / 10`)", + "units": "dps / 10" + } + ] }, - "payloadSize == OSD_CHAR_VISIBLE_BYTES + 1 (55 bytes)": { - "description": "8-bit character index with only the 54 visible bytes.", - "request": { - "payload": [ - { - "name": "address", - "ctype": "uint8_t", - "desc": "Character slot index (0-255)." - }, - { - "name": "charData", - "desc": "Visible pixel data only (no metadata).", - "ctype": "uint8_t", - "array": true, - "array_size": 54, - "array_size_define": "OSD_CHAR_VISIBLE_BYTES" - } - ] - }, - "reply": null - } - } - }, - "MSP_VTX_CONFIG": { - "code": 88, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "vtxDeviceType", - "ctype": "uint8_t", - "desc": "Enum (`vtxDevType_e`): Type of VTX device detected/configured. `VTXDEV_UNKNOWN` if none", - "units": "", - "enum": "vtxDevType_e" - }, - { - "name": "band", - "ctype": "uint8_t", - "desc": "VTX band number (from `vtxSettingsConfig`)", - "units": "" - }, - { - "name": "channel", - "ctype": "uint8_t", - "desc": "VTX channel number (from `vtxSettingsConfig`)", - "units": "" - }, - { - "name": "power", - "ctype": "uint8_t", - "desc": "VTX power level index (from `vtxSettingsConfig()`).", - "units": "" - }, - { - "name": "pitMode", - "ctype": "uint8_t", - "desc": "Boolean: 1 if VTX is currently in pit mode, 0 otherwise.", - "units": "" - }, - { - "name": "vtxReady", - "ctype": "uint8_t", - "desc": "Boolean: 1 if VTX device reported ready, 0 otherwise", - "units": "" - }, - { - "name": "lowPowerDisarm", - "ctype": "uint8_t", - "desc": "Enum `vtxLowerPowerDisarm_e`: Low-power behaviour while disarmed (`vtxSettingsConfig()->lowPowerDisarm`).", - "units": "Enum", - "enum": "vtxLowerPowerDisarm_e" - }, - { - "name": "vtxTableAvailable", - "ctype": "uint8_t", - "desc": "Boolean: 1 if VTX tables (band/power) are available for query", - "units": "" - }, - { - "name": "bandCount", - "ctype": "uint8_t", - "desc": "Number of bands supported by the VTX device", - "units": "" - }, - { - "name": "channelCount", - "ctype": "uint8_t", - "desc": "Number of channels per band supported by the VTX device", - "units": "" - }, - { - "name": "powerCount", - "ctype": "uint8_t", - "desc": "Number of power levels supported by the VTX device", - "units": "" - } - ] + "notes": "Acceleration limits are scaled by 10 for compatibility.", + "description": "Retrieves advanced PID tuning parameters. Many fields are BF compatibility placeholders." }, - "variable_len": true, - "notes": "Returns 1 byte (`VTXDEV_UNKNOWN`) when no VTX is detected or `USE_VTX_CONTROL` is disabled; otherwise sends full payload. BF compatibility field `frequency` (uint16) is missing compared to some BF versions. Use `MSP_VTXTABLE_BAND` and `MSP_VTXTABLE_POWERLEVEL` for details.", - "description": "Retrieves the current VTX (Video Transmitter) configuration and capabilities." - }, - "MSP_SET_VTX_CONFIG": { - "code": 89, - "mspv": 1, - "request": null, - "reply": null, - "variable_len": true, - "notes": "Requires dataSize >= 2. If no VTX device or device type is VTXDEV_UNKNOWN, fields are read and discarded. The first uint16 is interpreted as band/channel when value <= VTXCOMMON_MSP_BANDCHAN_CHKVAL, otherwise treated as a frequency value that is not applied by this path. Subsequent fields are applied only if present. If dataSize < 2 the command returns MSP_RESULT_ERROR.", - "description": "Sets VTX band/channel and related options. Fields are a progressive superset based on payload length.", - "variants": { - "payloadSize >= 14": { - "description": "Full payload (Betaflight 1.42+): includes explicit band/channel/frequency and capability counts.", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t", - "desc": "Encoded band/channel if <= `VTXCOMMON_MSP_BANDCHAN_CHKVAL`; otherwise frequency placeholder." - }, - { - "name": "power", - "ctype": "uint8_t" - }, - { - "name": "pitMode", - "ctype": "uint8_t" - }, - { - "name": "lowPowerDisarm", - "ctype": "uint8_t", - "enum": "vtxLowerPowerDisarm_e" - }, - { - "name": "pitModeFreq", - "ctype": "uint16_t" - }, - { - "name": "band", - "ctype": "uint8_t" - }, - { - "name": "channel", - "ctype": "uint8_t" - }, - { - "name": "frequency", - "ctype": "uint16_t" - }, - { - "name": "bandCount", - "ctype": "uint8_t", - "desc": "Read and ignored." - }, - { - "name": "channelCount", - "ctype": "uint8_t", - "desc": "Read and ignored." - }, - { - "name": "powerCount", - "ctype": "uint8_t", - "desc": "If 0 < value < current capability, caps `vtxDevice->capability.powerCount`." - } - ] - }, - "reply": null + "MSP_SET_PID_ADVANCED": { + "code": 95, + "mspv": 1, + "request": { + "payload": [ + { + "name": "legacyRollPitchItermIgnore", + "ctype": "uint16_t", + "desc": "Ignored (legacy compatibility)." + }, + { + "name": "legacyYawItermIgnore", + "ctype": "uint16_t", + "desc": "Ignored (legacy compatibility)." + }, + { + "name": "legacyYawPLimit", + "ctype": "uint16_t", + "desc": "Ignored (legacy compatibility)." + }, + { + "name": "bfCompatDeltaMethod", + "ctype": "uint8_t", + "desc": "Ignored (BF compatibility)." + }, + { + "name": "bfCompatVbatPidComp", + "ctype": "uint8_t", + "desc": "Ignored (BF compatibility)." + }, + { + "name": "bfCompatSetpointRelaxRatio", + "ctype": "uint8_t", + "desc": "Ignored (BF compatibility)." + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Ignored (reserved)." + }, + { + "name": "legacyPidSumLimit", + "ctype": "uint16_t", + "desc": "Ignored (legacy compatibility)." + }, + { + "name": "bfCompatItermThrottleGain", + "ctype": "uint8_t", + "desc": "Ignored (BF compatibility)." + }, + { + "name": "accelLimitRollPitch", + "ctype": "uint16_t", + "desc": "Sets `pidProfileMutable()->axisAccelerationLimitRollPitch = value * 10`.", + "units": "dps / 10" + }, + { + "name": "accelLimitYaw", + "ctype": "uint16_t", + "desc": "Sets `pidProfileMutable()->axisAccelerationLimitYaw = value * 10`.", + "units": "dps / 10" + } + ] }, - "payloadSize >= 11": { - "description": "Extends payload with explicit frequency.", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t" - }, - { - "name": "power", - "ctype": "uint8_t" - }, - { - "name": "pitMode", - "ctype": "uint8_t" - }, - { - "name": "lowPowerDisarm", - "ctype": "uint8_t", - "enum": "vtxLowerPowerDisarm_e" - }, - { - "name": "pitModeFreq", - "ctype": "uint16_t" - }, - { - "name": "band", - "ctype": "uint8_t" - }, - { - "name": "channel", - "ctype": "uint8_t" - }, - { - "name": "frequency", - "ctype": "uint16_t", - "desc": "Read and ignored by INAV." - } - ] - }, - "reply": null + "reply": null, + "notes": "Expects 17 bytes.", + "description": "Sets advanced PID tuning parameters." + }, + "MSP_SENSOR_CONFIG": { + "code": 96, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "accHardware", + "ctype": "uint8_t", + "desc": "Enum (`accelerationSensor_e`): Accelerometer hardware type (`accelerometerConfig()->acc_hardware`)", + "units": "", + "enum": "accelerationSensor_e" + }, + { + "name": "baroHardware", + "ctype": "uint8_t", + "desc": "Enum (`baroSensor_e`): Barometer hardware type (`barometerConfig()->baro_hardware`). 0 if `USE_BARO` disabled", + "units": "", + "enum": "baroSensor_e" + }, + { + "name": "magHardware", + "ctype": "uint8_t", + "desc": "Enum (`magSensor_e`): Magnetometer hardware type (`compassConfig()->mag_hardware`). 0 if `USE_MAG` disabled", + "units": "", + "enum": "magSensor_e" + }, + { + "name": "pitotHardware", + "ctype": "uint8_t", + "desc": "Enum (`pitotSensor_e`): Pitot tube hardware type (`pitotmeterConfig()->pitot_hardware`). 0 if `USE_PITOT` disabled", + "units": "", + "enum": "pitotSensor_e" + }, + { + "name": "rangefinderHardware", + "ctype": "uint8_t", + "desc": "Enum (`rangefinderType_e`): Rangefinder hardware type (`rangefinderConfig()->rangefinder_hardware`). 0 if `USE_RANGEFINDER` disabled", + "units": "", + "enum": "rangefinderType_e" + }, + { + "name": "opflowHardware", + "ctype": "uint8_t", + "desc": "Enum (`opticalFlowSensor_e`): Optical flow hardware type (`opticalFlowConfig()->opflow_hardware`). 0 if `USE_OPFLOW` disabled", + "units": "", + "enum": "opticalFlowSensor_e" + } + ] }, - "payloadSize >= 9": { - "description": "Adds explicit band/channel overrides (API 1.42 extension).", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t" - }, - { - "name": "power", - "ctype": "uint8_t" - }, - { - "name": "pitMode", - "ctype": "uint8_t" - }, - { - "name": "lowPowerDisarm", - "ctype": "uint8_t", - "enum": "vtxLowerPowerDisarm_e" - }, - { - "name": "pitModeFreq", - "ctype": "uint16_t" - }, - { - "name": "band", - "ctype": "uint8_t", - "desc": "1..N; overrides band when present." - }, - { - "name": "channel", - "ctype": "uint8_t", - "desc": "1..8; overrides channel when present." - } - ] - }, - "reply": null + "notes": "", + "description": "Retrieves the configured hardware type for various sensors." + }, + "MSP_SET_SENSOR_CONFIG": { + "code": 97, + "mspv": 1, + "request": { + "payload": [ + { + "name": "accHardware", + "ctype": "uint8_t", + "desc": "Sets `accelerometerConfigMutable()->acc_hardware`", + "units": "", + "enum": "accelerationSensor_e" + }, + { + "name": "baroHardware", + "ctype": "uint8_t", + "desc": "Sets `barometerConfigMutable()->baro_hardware` (if `USE_BARO`)", + "units": "", + "enum": "baroSensor_e" + }, + { + "name": "magHardware", + "ctype": "uint8_t", + "desc": "Sets `compassConfigMutable()->mag_hardware` (if `USE_MAG`)", + "units": "", + "enum": "magSensor_e" + }, + { + "name": "pitotHardware", + "ctype": "uint8_t", + "desc": "Sets `pitotmeterConfigMutable()->pitot_hardware` (if `USE_PITOT`)", + "units": "", + "enum": "pitotSensor_e" + }, + { + "name": "rangefinderHardware", + "ctype": "uint8_t", + "desc": "Sets `rangefinderConfigMutable()->rangefinder_hardware` (if `USE_RANGEFINDER`)", + "units": "", + "enum": "rangefinderType_e" + }, + { + "name": "opflowHardware", + "ctype": "uint8_t", + "desc": "Sets `opticalFlowConfigMutable()->opflow_hardware` (if `USE_OPFLOW`)", + "units": "", + "enum": "opticalFlowSensor_e" + } + ] }, - "payloadSize >= 7": { - "description": "Adds pit-mode frequency placeholder.", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t" - }, - { - "name": "power", - "ctype": "uint8_t" - }, - { - "name": "pitMode", - "ctype": "uint8_t" - }, - { - "name": "lowPowerDisarm", - "ctype": "uint8_t", - "enum": "vtxLowerPowerDisarm_e" - }, - { - "name": "pitModeFreq", - "ctype": "uint16_t", - "desc": "Read and skipped." - } - ] - }, - "reply": null + "reply": null, + "notes": "Expects 6 bytes.", + "description": "Sets the configured hardware type for various sensors." + }, + "MSP_SPECIAL_PARAMETERS": { + "code": 98, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`.", + "description": "Betaflight specific" + }, + "MSP_SET_SPECIAL_PARAMETERS": { + "code": 99, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`.", + "description": "Betaflight specific" + }, + "MSP_IDENT": { + "code": 100, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": { + "payload": [ + { + "name": "MultiWii version", + "ctype": "uint8_t", + "desc": "Scaled version major*100+minor", + "units": "n/a" + }, + { + "name": "Mixer Mode", + "ctype": "uint8_t", + "desc": "Mixer type", + "units": "Enum" + }, + { + "name": "MSP Version", + "ctype": "uint8_t", + "desc": "Scaled version major*100+minor", + "units": "n/a" + }, + { + "name": "Platform Capability", + "ctype": "uint32_t", + "desc": "Bitmask: MW capabilities", + "units": "Bitmask", + "bitmask": true + } + ] }, - "payloadSize >= 5": { - "description": "Adds low-power disarm behaviour.", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t" - }, - { - "name": "power", - "ctype": "uint8_t" - }, - { - "name": "pitMode", - "ctype": "uint8_t" - }, - { - "name": "lowPowerDisarm", - "ctype": "uint8_t", - "enum": "vtxLowerPowerDisarm_e", - "desc": "0=Off, 1=Always, 2=Until first arm." - } - ] - }, - "reply": null + "notes": "Obsolete. Listed for legacy compatibility only.", + "description": "Provides basic flight controller identity information. Not implemented in modern INAV, but used by legacy versions and MultiWii." + }, + "MSP_STATUS": { + "code": 101, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "cycleTime", + "ctype": "uint16_t", + "desc": "Main loop cycle time (`cycleTime`)", + "units": "Β΅s" + }, + { + "name": "i2cErrors", + "ctype": "uint16_t", + "desc": "Number of I2C errors encountered (`i2cGetErrorCounter()`). 0 if `USE_I2C` not defined", + "units": "Count" + }, + { + "name": "sensorStatus", + "ctype": "uint16_t", + "desc": "Bitmask: available/active sensors (`packSensorStatus()`). See notes", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "activeModesLow", + "ctype": "uint32_t", + "desc": "Bitmask: First 32 bits of the active flight modes bitmask (`packBoxModeFlags()`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "profile", + "ctype": "uint8_t", + "desc": "Current configuration profile index (0-based) (`getConfigProfile()`)", + "units": "Index" + } + ] }, - "payloadSize >= 4": { - "description": "Adds power index and pit mode flag.", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t" - }, - { - "name": "power", - "ctype": "uint8_t" - }, - { - "name": "pitMode", - "ctype": "uint8_t" - } - ] - }, - "reply": null + "notes": "Superseded by `MSP_STATUS_EX` and `MSP2_INAV_STATUS`. `sensorStatus` bitmask: (Bit 0: ACC, 1: BARO, 2: MAG, 3: GPS, 4: RANGEFINDER, 5: OPFLOW, 6: PITOT, 7: TEMP; Bit 15: hardware failure). `activeModesLow` only contains the first 32 modes; use `MSP_ACTIVEBOXES` for the full set.", + "description": "Provides basic flight controller status including cycle time, errors, sensor status, active modes (first 32), and the current configuration profile." + }, + "MSP_RAW_IMU": { + "code": 102, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "accX", + "ctype": "int16_t", + "desc": "Raw accelerometer X reading, scaled (`acc.accADCf[X] * 512`)", + "units": "~1/512 G" + }, + { + "name": "accY", + "ctype": "int16_t", + "desc": "Raw accelerometer Y reading, scaled (`acc.accADCf[Y] * 512`)", + "units": "~1/512 G" + }, + { + "name": "accZ", + "ctype": "int16_t", + "desc": "Raw accelerometer Z reading, scaled (`acc.accADCf[Z] * 512`)", + "units": "~1/512 G" + }, + { + "name": "gyroX", + "ctype": "int16_t", + "desc": "Gyroscope X-axis rate (`gyroRateDps(X)`)", + "units": "deg/s" + }, + { + "name": "gyroY", + "ctype": "int16_t", + "desc": "Gyroscope Y-axis rate (`gyroRateDps(Y)`)", + "units": "deg/s" + }, + { + "name": "gyroZ", + "ctype": "int16_t", + "desc": "Gyroscope Z-axis rate (`gyroRateDps(Z)`)", + "units": "deg/s" + }, + { + "name": "magX", + "ctype": "int16_t", + "desc": "Raw magnetometer X reading (`mag.magADC[X]`). 0 if `USE_MAG` disabled", + "units": "Raw units" + }, + { + "name": "magY", + "ctype": "int16_t", + "desc": "Raw magnetometer Y reading (`mag.magADC[Y]`). 0 if `USE_MAG` disabled", + "units": "Raw units" + }, + { + "name": "magZ", + "ctype": "int16_t", + "desc": "Raw magnetometer Z reading (`mag.magADC[Z]`). 0 if `USE_MAG` disabled", + "units": "Raw units" + } + ] }, - "payloadSize == 2": { - "description": "Minimum payload (band/channel encoded in 0..63).", - "request": { - "payload": [ - { - "name": "bandChanOrFreq", - "ctype": "uint16_t", - "desc": "If <= `VTXCOMMON_MSP_BANDCHAN_CHKVAL`, decoded as band/channel; otherwise treated as a frequency placeholder." - } - ] - }, - "reply": null - } - } - }, - "MSP_ADVANCED_CONFIG": { - "code": 90, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "gyroSyncDenom", - "ctype": "uint8_t", - "desc": "Always 1 (BF compatibility)", - "units": "", - "value": 1 - }, - { - "name": "pidProcessDenom", - "ctype": "uint8_t", - "desc": "Always 1 (BF compatibility)", - "units": "", - "value": 1 - }, - { - "name": "useUnsyncedPwm", - "ctype": "uint8_t", - "desc": "Always 1 (BF compatibility, INAV uses async PWM based on protocol)", - "units": "", - "value": 1 - }, - { - "name": "motorPwmProtocol", - "ctype": "uint8_t", - "desc": "Motor PWM protocol type (`motorConfig()->motorPwmProtocol`).", - "units": "Enum", - "enum": "motorPwmProtocolTypes_e" - }, - { - "name": "motorPwmRate", - "ctype": "uint16_t", - "desc": "Motor PWM rate (if applicable) (`motorConfig()->motorPwmRate`).", - "units": "Hz" - }, - { - "name": "servoPwmRate", - "ctype": "uint16_t", - "desc": "Servo PWM rate (`servoConfig()->servoPwmRate`).", - "units": "Hz" - }, - { - "name": "legacyGyroSync", - "ctype": "uint8_t", - "desc": "Always 0 (BF compatibility)", - "units": "", - "value": 0 - } - ] - }, - "notes": "", - "description": "Retrieves advanced hardware-related configuration (PWM protocols, rates). Some fields are BF compatibility placeholders." - }, - "MSP_SET_ADVANCED_CONFIG": { - "code": 91, - "mspv": 1, - "request": { - "payload": [ - { - "name": "gyroSyncDenom", - "ctype": "uint8_t", - "desc": "Ignored (legacy Betaflight field).", - "units": "" - }, - { - "name": "pidProcessDenom", - "ctype": "uint8_t", - "desc": "Ignored (legacy Betaflight field).", - "units": "" - }, - { - "name": "useUnsyncedPwm", - "ctype": "uint8_t", - "desc": "Ignored (legacy Betaflight field).", - "units": "" - }, - { - "name": "motorPwmProtocol", - "ctype": "uint8_t", - "desc": "Sets `motorConfigMutable()->motorPwmProtocol`.", - "units": "Enum", - "enum": "motorPwmProtocolTypes_e" - }, - { - "name": "motorPwmRate", - "ctype": "uint16_t", - "desc": "Sets `motorConfigMutable()->motorPwmRate`.", - "units": "Hz" - }, - { - "name": "servoPwmRate", - "ctype": "uint16_t", - "desc": "Sets `servoConfigMutable()->servoPwmRate`.", - "units": "Hz" - }, - { - "name": "legacyGyroSync", - "ctype": "uint8_t", - "desc": "Ignored (legacy Betaflight field).", - "units": "" - } - ] - }, - "reply": null, - "notes": "Expects 9 bytes.", - "description": "Sets advanced hardware-related configuration (PWM protocols, rates)." - }, - "MSP_FILTER_CONFIG": { - "code": 92, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "gyroMainLpfHz", - "ctype": "uint8_t", - "desc": "Gyro main low-pass filter cutoff frequency (`gyroConfig()->gyro_main_lpf_hz`)", - "units": "Hz" - }, - { - "name": "dtermLpfHz", - "ctype": "uint16_t", - "desc": "D-term low-pass filter cutoff frequency (`pidProfile()->dterm_lpf_hz`)", - "units": "Hz" - }, - { - "name": "yawLpfHz", - "ctype": "uint16_t", - "desc": "Yaw low-pass filter cutoff frequency (`pidProfile()->yaw_lpf_hz`)", - "units": "Hz" - }, - { - "name": "legacyGyroNotchHz", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "legacyGyroNotchCutoff", - "ctype": "uint16_t", - "desc": "Always 1 (Legacy)", - "value": 1 - }, - { - "name": "bfCompatDtermNotchHz", - "ctype": "uint16_t", - "desc": "Always 0 (BF compatibility)", - "value": 0 - }, - { - "name": "bfCompatDtermNotchCutoff", - "ctype": "uint16_t", - "desc": "Always 1 (BF compatibility)", - "value": 1 - }, - { - "name": "bfCompatGyroNotch2Hz", - "ctype": "uint16_t", - "desc": "Always 0 (BF compatibility)", - "value": 0 - }, - { - "name": "bfCompatGyroNotch2Cutoff", - "ctype": "uint16_t", - "desc": "Always 1 (BF compatibility)", - "value": 1 - }, - { - "name": "accNotchHz", - "ctype": "uint16_t", - "desc": "Accelerometer notch filter center frequency (`accelerometerConfig()->acc_notch_hz`)", - "units": "Hz" - }, - { - "name": "accNotchCutoff", - "ctype": "uint16_t", - "desc": "Accelerometer notch filter cutoff frequency (`accelerometerConfig()->acc_notch_cutoff`)", - "units": "Hz" - }, - { - "name": "legacyGyroStage2LpfHz", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - } - ] - }, - "notes": "", - "description": "Retrieves filter configuration settings (Gyro, D-term, Yaw, Accel). Some fields are BF compatibility placeholders or legacy." - }, - "MSP_SET_FILTER_CONFIG": { - "code": 93, - "mspv": 1, - "request": { - "payload": [ - { - "name": "gyroMainLpfHz", - "ctype": "uint8_t", - "desc": "Sets `gyroConfigMutable()->gyro_main_lpf_hz`. (Size >= 5)", - "units": "Hz" - }, - { - "name": "dtermLpfHz", - "ctype": "uint16_t", - "desc": "Sets `pidProfileMutable()->dterm_lpf_hz` (constrained 0-500). (Size >= 5)", - "units": "Hz" - }, - { - "name": "yawLpfHz", - "ctype": "uint16_t", - "desc": "Sets `pidProfileMutable()->yaw_lpf_hz` (constrained 0-255). (Size >= 5)", - "units": "Hz" - }, - { - "name": "legacyGyroNotchHz", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 9)" - }, - { - "name": "legacyGyroNotchCutoff", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 9)" - }, - { - "name": "bfCompatDtermNotchHz", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 13)" - }, - { - "name": "bfCompatDtermNotchCutoff", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 13)" - }, - { - "name": "bfCompatGyroNotch2Hz", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 17)" - }, - { - "name": "bfCompatGyroNotch2Cutoff", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 17)" - }, - { - "name": "accNotchHz", - "ctype": "uint16_t", - "desc": "Sets `accelerometerConfigMutable()->acc_notch_hz` (constrained 0-255). (Size >= 21)", - "units": "Hz" - }, - { - "name": "accNotchCutoff", - "ctype": "uint16_t", - "desc": "Sets `accelerometerConfigMutable()->acc_notch_cutoff` (constrained 1-255). (Size >= 21)", - "units": "Hz" - }, - { - "name": "legacyGyroStage2LpfHz", - "ctype": "uint16_t", - "desc": "Ignored. (Size >= 22)" - } - ] - }, - "reply": null, - "notes": "Requires at least 22 bytes; intermediate length checks enforce legacy Betaflight frame layout and call `pidInitFilters()` once the D-term notch placeholders are consumed.", - "description": "Sets filter configuration settings. Handles different payload lengths for backward compatibility." - }, - "MSP_PID_ADVANCED": { - "code": 94, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "legacyRollPitchItermIgnore", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "legacyYawItermIgnore", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "legacyYawPLimit", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "bfCompatDeltaMethod", - "ctype": "uint8_t", - "desc": "Always 0 (BF compatibility)", - "value": 0 - }, - { - "name": "bfCompatVbatPidComp", - "ctype": "uint8_t", - "desc": "Always 0 (BF compatibility)", - "value": 0 - }, - { - "name": "bfCompatSetpointRelaxRatio", - "ctype": "uint8_t", - "desc": "Always 0 (BF compatibility)", - "value": 0 - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Always 0", - "value": 0 - }, - { - "name": "legacyPidSumLimit", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "bfCompatItermThrottleGain", - "ctype": "uint8_t", - "desc": "Always 0 (BF compatibility)", - "value": 0 - }, - { - "name": "accelLimitRollPitch", - "ctype": "uint16_t", - "desc": "Axis acceleration limit for Roll/Pitch / 10 (`pidProfile()->axisAccelerationLimitRollPitch / 10`)", - "units": "dps / 10" - }, - { - "name": "accelLimitYaw", - "ctype": "uint16_t", - "desc": "Axis acceleration limit for Yaw / 10 (`pidProfile()->axisAccelerationLimitYaw / 10`)", - "units": "dps / 10" - } - ] - }, - "notes": "Acceleration limits are scaled by 10 for compatibility.", - "description": "Retrieves advanced PID tuning parameters. Many fields are BF compatibility placeholders." - }, - "MSP_SET_PID_ADVANCED": { - "code": 95, - "mspv": 1, - "request": { - "payload": [ - { - "name": "legacyRollPitchItermIgnore", - "ctype": "uint16_t", - "desc": "Ignored (legacy compatibility)." - }, - { - "name": "legacyYawItermIgnore", - "ctype": "uint16_t", - "desc": "Ignored (legacy compatibility)." - }, - { - "name": "legacyYawPLimit", - "ctype": "uint16_t", - "desc": "Ignored (legacy compatibility)." - }, - { - "name": "bfCompatDeltaMethod", - "ctype": "uint8_t", - "desc": "Ignored (BF compatibility)." - }, - { - "name": "bfCompatVbatPidComp", - "ctype": "uint8_t", - "desc": "Ignored (BF compatibility)." - }, - { - "name": "bfCompatSetpointRelaxRatio", - "ctype": "uint8_t", - "desc": "Ignored (BF compatibility)." - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Ignored (reserved)." - }, - { - "name": "legacyPidSumLimit", - "ctype": "uint16_t", - "desc": "Ignored (legacy compatibility)." - }, - { - "name": "bfCompatItermThrottleGain", - "ctype": "uint8_t", - "desc": "Ignored (BF compatibility)." - }, - { - "name": "accelLimitRollPitch", - "ctype": "uint16_t", - "desc": "Sets `pidProfileMutable()->axisAccelerationLimitRollPitch = value * 10`.", - "units": "dps / 10" - }, - { - "name": "accelLimitYaw", - "ctype": "uint16_t", - "desc": "Sets `pidProfileMutable()->axisAccelerationLimitYaw = value * 10`.", - "units": "dps / 10" - } - ] - }, - "reply": null, - "notes": "Expects 17 bytes.", - "description": "Sets advanced PID tuning parameters." - }, - "MSP_SENSOR_CONFIG": { - "code": 96, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "accHardware", - "ctype": "uint8_t", - "desc": "Enum (`accelerationSensor_e`): Accelerometer hardware type (`accelerometerConfig()->acc_hardware`)", - "units": "", - "enum": "accelerationSensor_e" - }, - { - "name": "baroHardware", - "ctype": "uint8_t", - "desc": "Enum (`baroSensor_e`): Barometer hardware type (`barometerConfig()->baro_hardware`). 0 if `USE_BARO` disabled", - "units": "", - "enum": "baroSensor_e" - }, - { - "name": "magHardware", - "ctype": "uint8_t", - "desc": "Enum (`magSensor_e`): Magnetometer hardware type (`compassConfig()->mag_hardware`). 0 if `USE_MAG` disabled", - "units": "", - "enum": "magSensor_e" - }, - { - "name": "pitotHardware", - "ctype": "uint8_t", - "desc": "Enum (`pitotSensor_e`): Pitot tube hardware type (`pitotmeterConfig()->pitot_hardware`). 0 if `USE_PITOT` disabled", - "units": "", - "enum": "pitotSensor_e" - }, - { - "name": "rangefinderHardware", - "ctype": "uint8_t", - "desc": "Enum (`rangefinderType_e`): Rangefinder hardware type (`rangefinderConfig()->rangefinder_hardware`). 0 if `USE_RANGEFINDER` disabled", - "units": "", - "enum": "rangefinderType_e" - }, - { - "name": "opflowHardware", - "ctype": "uint8_t", - "desc": "Enum (`opticalFlowSensor_e`): Optical flow hardware type (`opticalFlowConfig()->opflow_hardware`). 0 if `USE_OPFLOW` disabled", - "units": "", - "enum": "opticalFlowSensor_e" - } - ] - }, - "notes": "", - "description": "Retrieves the configured hardware type for various sensors." - }, - "MSP_SET_SENSOR_CONFIG": { - "code": 97, - "mspv": 1, - "request": { - "payload": [ - { - "name": "accHardware", - "ctype": "uint8_t", - "desc": "Sets `accelerometerConfigMutable()->acc_hardware`", - "units": "", - "enum": "accelerationSensor_e" - }, - { - "name": "baroHardware", - "ctype": "uint8_t", - "desc": "Sets `barometerConfigMutable()->baro_hardware` (if `USE_BARO`)", - "units": "", - "enum": "baroSensor_e" - }, - { - "name": "magHardware", - "ctype": "uint8_t", - "desc": "Sets `compassConfigMutable()->mag_hardware` (if `USE_MAG`)", - "units": "", - "enum": "magSensor_e" - }, - { - "name": "pitotHardware", - "ctype": "uint8_t", - "desc": "Sets `pitotmeterConfigMutable()->pitot_hardware` (if `USE_PITOT`)", - "units": "", - "enum": "pitotSensor_e" - }, - { - "name": "rangefinderHardware", - "ctype": "uint8_t", - "desc": "Sets `rangefinderConfigMutable()->rangefinder_hardware` (if `USE_RANGEFINDER`)", - "units": "", - "enum": "rangefinderType_e" - }, - { - "name": "opflowHardware", - "ctype": "uint8_t", - "desc": "Sets `opticalFlowConfigMutable()->opflow_hardware` (if `USE_OPFLOW`)", - "units": "", - "enum": "opticalFlowSensor_e" - } - ] - }, - "reply": null, - "notes": "Expects 6 bytes.", - "description": "Sets the configured hardware type for various sensors." - }, - "MSP_SPECIAL_PARAMETERS": { - "code": 98, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`.", - "description": "Betaflight specific" - }, - "MSP_SET_SPECIAL_PARAMETERS": { - "code": 99, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`.", - "description": "Betaflight specific" - }, - "MSP_IDENT": { - "code": 100, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": { - "payload": [ - { - "name": "MultiWii version", - "ctype": "uint8_t", - "desc": "Scaled version major*100+minor", - "units": "n/a" - }, - { - "name": "Mixer Mode", - "ctype": "uint8_t", - "desc": "Mixer type", - "units": "Enum" - }, - { - "name": "MSP Version", - "ctype": "uint8_t", - "desc": "Scaled version major*100+minor", - "units": "n/a" - }, - { - "name": "Platform Capability", - "ctype": "uint32_t", - "desc": "Bitmask: MW capabilities", - "units": "Bitmask", - "bitmask": true - } - ] - }, - "notes": "Obsolete. Listed for legacy compatibility only.", - "description": "Provides basic flight controller identity information. Not implemented in modern INAV, but used by legacy versions and MultiWii." - }, - "MSP_STATUS": { - "code": 101, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "cycleTime", - "ctype": "uint16_t", - "desc": "Main loop cycle time (`cycleTime`)", - "units": "Β΅s" - }, - { - "name": "i2cErrors", - "ctype": "uint16_t", - "desc": "Number of I2C errors encountered (`i2cGetErrorCounter()`). 0 if `USE_I2C` not defined", - "units": "Count" - }, - { - "name": "sensorStatus", - "ctype": "uint16_t", - "desc": "Bitmask: available/active sensors (`packSensorStatus()`). See notes", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "activeModesLow", - "ctype": "uint32_t", - "desc": "Bitmask: First 32 bits of the active flight modes bitmask (`packBoxModeFlags()`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "profile", - "ctype": "uint8_t", - "desc": "Current configuration profile index (0-based) (`getConfigProfile()`)", - "units": "Index" - } - ] - }, - "notes": "Superseded by `MSP_STATUS_EX` and `MSP2_INAV_STATUS`. `sensorStatus` bitmask: (Bit 0: ACC, 1: BARO, 2: MAG, 3: GPS, 4: RANGEFINDER, 5: OPFLOW, 6: PITOT, 7: TEMP; Bit 15: hardware failure). `activeModesLow` only contains the first 32 modes; use `MSP_ACTIVEBOXES` for the full set.", - "description": "Provides basic flight controller status including cycle time, errors, sensor status, active modes (first 32), and the current configuration profile." - }, - "MSP_RAW_IMU": { - "code": 102, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "accX", - "ctype": "int16_t", - "desc": "Raw accelerometer X reading, scaled (`acc.accADCf[X] * 512`)", - "units": "~1/512 G" - }, - { - "name": "accY", - "ctype": "int16_t", - "desc": "Raw accelerometer Y reading, scaled (`acc.accADCf[Y] * 512`)", - "units": "~1/512 G" - }, - { - "name": "accZ", - "ctype": "int16_t", - "desc": "Raw accelerometer Z reading, scaled (`acc.accADCf[Z] * 512`)", - "units": "~1/512 G" - }, - { - "name": "gyroX", - "ctype": "int16_t", - "desc": "Gyroscope X-axis rate (`gyroRateDps(X)`)", - "units": "deg/s" - }, - { - "name": "gyroY", - "ctype": "int16_t", - "desc": "Gyroscope Y-axis rate (`gyroRateDps(Y)`)", - "units": "deg/s" - }, - { - "name": "gyroZ", - "ctype": "int16_t", - "desc": "Gyroscope Z-axis rate (`gyroRateDps(Z)`)", - "units": "deg/s" - }, - { - "name": "magX", - "ctype": "int16_t", - "desc": "Raw magnetometer X reading (`mag.magADC[X]`). 0 if `USE_MAG` disabled", - "units": "Raw units" - }, - { - "name": "magY", - "ctype": "int16_t", - "desc": "Raw magnetometer Y reading (`mag.magADC[Y]`). 0 if `USE_MAG` disabled", - "units": "Raw units" - }, - { - "name": "magZ", - "ctype": "int16_t", - "desc": "Raw magnetometer Z reading (`mag.magADC[Z]`). 0 if `USE_MAG` disabled", - "units": "Raw units" - } - ] - }, - "notes": "Acc scaling is approximate (512 LSB/G). Mag units depend on the sensor.", - "description": "Provides raw sensor readings from the IMU (Accelerometer, Gyroscope, Magnetometer)." - }, - "MSP_SERVO": { - "code": 103, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "servoOutputs", - "desc": "Array of current servo output values (typically 1000-2000)", - "ctype": "int16_t", - "array": true, - "array_size": 18, - "array_size_define": "MAX_SUPPORTED_SERVOS", - "units": "PWM" - } - ] - }, - "variable_len": true, - "notes": "", - "description": "Provides the current output values for all supported servos." - }, - "MSP_MOTOR": { - "code": 104, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "motorOutputs", - "desc": "Array of current motor output values (typically 1000-2000). Values beyond `MAX_SUPPORTED_MOTORS` are 0", - "ctype": "int16_t", - "array": true, - "array_size": 8, - "units": "PWM" - } - ] - }, - "notes": "", - "description": "Provides the current output values for the first 8 motors." - }, - "MSP_RC": { - "code": 105, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "rcChannels", - "desc": "Array of current RC channel values (typically 1000-2000). Length depends on detected channels", - "ctype": "int16_t", - "array": true, - "array_size": 0, - "units": "PWM" - } - ] - }, - "variable_len": true, - "notes": "Array length equals `rxRuntimeConfig.channelCount`.", - "description": "Provides the current values of the received RC channels." - }, - "MSP_RAW_GPS": { - "code": 106, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "fixType", - "ctype": "uint8_t", - "desc": "Enum `gpsFixType_e` GPS fix type (`gpsSol.fixType`)", - "units": "Enum", - "enum": "gpsFixType_e" - }, - { - "name": "numSat", - "ctype": "uint8_t", - "desc": "Number of satellites used in solution (`gpsSol.numSat`)", - "units": "Count" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude (`gpsSol.llh.lat`)", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude (`gpsSol.llh.lon`)", - "units": "deg * 1e7" - }, - { - "name": "altitude", - "ctype": "int16_t", - "desc": "Altitude above MSL (`gpsSol.llh.alt`) sent as centimeters", - "units": "cm" - }, - { - "name": "speed", - "ctype": "int16_t", - "desc": "Ground speed (`gpsSol.groundSpeed`)", - "units": "cm/s" - }, - { - "name": "groundCourse", - "ctype": "int16_t", - "desc": "Ground course (`gpsSol.groundCourse`)", - "units": "deci-degrees" - }, - { - "name": "hdop", - "ctype": "uint16_t", - "desc": "Horizontal Dilution of Precision (`gpsSol.hdop`)", - "units": "HDOP * 100" - } - ] - }, - "notes": "Only available if `USE_GPS` is defined. Altitude is truncated to meters.", - "description": "Provides raw GPS data (fix status, coordinates, altitude, speed, course)." - }, - "MSP_COMP_GPS": { - "code": 107, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "distanceToHome", - "ctype": "uint16_t", - "desc": "Distance to the home point (`GPS_distanceToHome`)", - "units": "meters" - }, - { - "name": "directionToHome", - "ctype": "int16_t", - "desc": "Direction to the home point (0-360) (`GPS_directionToHome`)", - "units": "degrees" - }, - { - "name": "gpsHeartbeat", - "ctype": "uint8_t", - "desc": "Indicates if GPS data is being received (`gpsSol.flags.gpsHeartbeat`)", - "units": "Boolean" - } - ] - }, - "notes": "Only available if `USE_GPS` is defined.", - "description": "Provides computed GPS values: distance and direction to home." - }, - "MSP_ATTITUDE": { - "code": 108, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "roll", - "ctype": "int16_t", - "desc": "Roll angle (`attitude.values.roll`)", - "units": "deci-degrees" - }, - { - "name": "pitch", - "ctype": "int16_t", - "desc": "Pitch angle (`attitude.values.pitch`)", - "units": "deci-degrees" - }, - { - "name": "yaw", - "ctype": "int16_t", - "desc": "Yaw/Heading angle (`DECIDEGREES_TO_DEGREES(attitude.values.yaw)`)", - "units": "degrees" - } - ] - }, - "notes": "Yaw is in degrees.", - "description": "Provides the current attitude estimate (roll, pitch, yaw)." - }, - "MSP_ALTITUDE": { - "code": 109, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "estimatedAltitude", - "ctype": "int32_t", - "desc": "Estimated altitude above home/sea level (`getEstimatedActualPosition(Z)`)", - "units": "cm" - }, - { - "name": "variometer", - "ctype": "int16_t", - "desc": "Estimated vertical speed (`getEstimatedActualVelocity(Z)`)", - "units": "cm/s" - }, - { - "name": "baroAltitude", - "ctype": "int32_t", - "desc": "Latest raw altitude from barometer (`baroGetLatestAltitude()`). 0 if `USE_BARO` disabled", - "units": "cm" - } - ] - }, - "notes": "", - "description": "Provides estimated altitude, vertical speed (variometer), and raw barometric altitude." - }, - "MSP_ANALOG": { - "code": 110, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "vbat", - "ctype": "uint8_t", - "desc": "Battery voltage, scaled (`getBatteryVoltage() / 10`), constrained 0-255", - "units": "0.1V" - }, - { - "name": "mAhDrawn", - "ctype": "uint16_t", - "desc": "Consumed battery capacity (`getMAhDrawn()`), constrained 0-65535", - "units": "mAh" - }, - { - "name": "rssi", - "ctype": "uint16_t", - "desc": "Received Signal Strength Indicator (`getRSSI()`). Units depend on source", - "units": "0-1023 or %" - }, - { - "name": "amperage", - "ctype": "int16_t", - "desc": "Current draw (`getAmperage()`), constrained -32768 to 32767", - "units": "0.01A" - } - ] + "notes": "Acc scaling is approximate (512 LSB/G). Mag units depend on the sensor.", + "description": "Provides raw sensor readings from the IMU (Accelerometer, Gyroscope, Magnetometer)." + }, + "MSP_SERVO": { + "code": 103, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "servoOutputs", + "desc": "Array of current servo output values (typically 1000-2000)", + "ctype": "int16_t", + "array": true, + "array_size": 18, + "array_size_define": "MAX_SUPPORTED_SERVOS", + "units": "PWM" + } + ] + }, + "variable_len": true, + "notes": "", + "description": "Provides the current output values for all supported servos." + }, + "MSP_MOTOR": { + "code": 104, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "motorOutputs", + "desc": "Array of current motor output values (typically 1000-2000). Values beyond `MAX_SUPPORTED_MOTORS` are 0", + "ctype": "int16_t", + "array": true, + "array_size": 8, + "units": "PWM" + } + ] + }, + "notes": "", + "description": "Provides the current output values for the first 8 motors." + }, + "MSP_RC": { + "code": 105, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "rcChannels", + "desc": "Array of current RC channel values (typically 1000-2000). Length depends on detected channels", + "ctype": "int16_t", + "array": true, + "array_size": 0, + "units": "PWM" + } + ] + }, + "variable_len": true, + "notes": "Array length equals `rxRuntimeConfig.channelCount`.", + "description": "Provides the current values of the received RC channels." + }, + "MSP_RAW_GPS": { + "code": 106, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "fixType", + "ctype": "uint8_t", + "desc": "Enum `gpsFixType_e` GPS fix type (`gpsSol.fixType`)", + "units": "Enum", + "enum": "gpsFixType_e" + }, + { + "name": "numSat", + "ctype": "uint8_t", + "desc": "Number of satellites used in solution (`gpsSol.numSat`)", + "units": "Count" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude (`gpsSol.llh.lat`)", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude (`gpsSol.llh.lon`)", + "units": "deg * 1e7" + }, + { + "name": "altitude", + "ctype": "int16_t", + "desc": "Altitude above MSL (`gpsSol.llh.alt`) sent as centimeters", + "units": "cm" + }, + { + "name": "speed", + "ctype": "int16_t", + "desc": "Ground speed (`gpsSol.groundSpeed`)", + "units": "cm/s" + }, + { + "name": "groundCourse", + "ctype": "int16_t", + "desc": "Ground course (`gpsSol.groundCourse`)", + "units": "deci-degrees" + }, + { + "name": "hdop", + "ctype": "uint16_t", + "desc": "Horizontal Dilution of Precision (`gpsSol.hdop`)", + "units": "HDOP * 100" + } + ] + }, + "notes": "Only available if `USE_GPS` is defined. Altitude is truncated to meters.", + "description": "Provides raw GPS data (fix status, coordinates, altitude, speed, course)." + }, + "MSP_COMP_GPS": { + "code": 107, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "distanceToHome", + "ctype": "uint16_t", + "desc": "Distance to the home point (`GPS_distanceToHome`)", + "units": "meters" + }, + { + "name": "directionToHome", + "ctype": "int16_t", + "desc": "Direction to the home point (0-360) (`GPS_directionToHome`)", + "units": "degrees" + }, + { + "name": "gpsHeartbeat", + "ctype": "uint8_t", + "desc": "Indicates if GPS data is being received (`gpsSol.flags.gpsHeartbeat`)", + "units": "Boolean" + } + ] + }, + "notes": "Only available if `USE_GPS` is defined.", + "description": "Provides computed GPS values: distance and direction to home." + }, + "MSP_ATTITUDE": { + "code": 108, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "roll", + "ctype": "int16_t", + "desc": "Roll angle (`attitude.values.roll`)", + "units": "deci-degrees" + }, + { + "name": "pitch", + "ctype": "int16_t", + "desc": "Pitch angle (`attitude.values.pitch`)", + "units": "deci-degrees" + }, + { + "name": "yaw", + "ctype": "int16_t", + "desc": "Yaw/Heading angle (`DECIDEGREES_TO_DEGREES(attitude.values.yaw)`)", + "units": "degrees" + } + ] + }, + "notes": "Yaw is in degrees.", + "description": "Provides the current attitude estimate (roll, pitch, yaw)." + }, + "MSP_ALTITUDE": { + "code": 109, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "estimatedAltitude", + "ctype": "int32_t", + "desc": "Estimated altitude above home/sea level (`getEstimatedActualPosition(Z)`)", + "units": "cm" + }, + { + "name": "variometer", + "ctype": "int16_t", + "desc": "Estimated vertical speed (`getEstimatedActualVelocity(Z)`)", + "units": "cm/s" + }, + { + "name": "baroAltitude", + "ctype": "int32_t", + "desc": "Latest raw altitude from barometer (`baroGetLatestAltitude()`). 0 if `USE_BARO` disabled", + "units": "cm" + } + ] + }, + "notes": "", + "description": "Provides estimated altitude, vertical speed (variometer), and raw barometric altitude." + }, + "MSP_ANALOG": { + "code": 110, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "vbat", + "ctype": "uint8_t", + "desc": "Battery voltage, scaled (`getBatteryVoltage() / 10`), constrained 0-255", + "units": "0.1V" + }, + { + "name": "mAhDrawn", + "ctype": "uint16_t", + "desc": "Consumed battery capacity (`getMAhDrawn()`), constrained 0-65535", + "units": "mAh" + }, + { + "name": "rssi", + "ctype": "uint16_t", + "desc": "Received Signal Strength Indicator (`getRSSI()`). Units depend on source", + "units": "0-1023 or %" + }, + { + "name": "amperage", + "ctype": "int16_t", + "desc": "Current draw (`getAmperage()`), constrained -32768 to 32767", + "units": "0.01A" + } + ] + }, + "notes": "Superseded by `MSP2_INAV_ANALOG` which provides higher precision and more fields.", + "description": "Provides analog sensor readings: battery voltage, current consumption (mAh), RSSI, and current draw (Amps)." + }, + "MSP_RC_TUNING": { + "code": 111, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "legacyRcRate", + "ctype": "uint8_t", + "desc": "Always 100 (Legacy, unused)", + "units": "", + "value": 100 + }, + { + "name": "rcExpo", + "ctype": "uint8_t", + "desc": "Roll/Pitch RC Expo (`currentControlRateProfile->stabilized.rcExpo8`)", + "units": "" + }, + { + "name": "rollRate", + "ctype": "uint8_t", + "desc": "Roll Rate (`currentControlRateProfile->stabilized.rates[FD_ROLL]`)", + "units": "" + }, + { + "name": "pitchRate", + "ctype": "uint8_t", + "desc": "Pitch Rate (`currentControlRateProfile->stabilized.rates[FD_PITCH]`)", + "units": "" + }, + { + "name": "yawRate", + "ctype": "uint8_t", + "desc": "Yaw Rate (`currentControlRateProfile->stabilized.rates[FD_YAW]`)", + "units": "" + }, + { + "name": "dynamicThrottlePID", + "ctype": "uint8_t", + "desc": "Dynamic Throttle PID (TPA) value (`currentControlRateProfile->throttle.dynPID`)", + "units": "" + }, + { + "name": "throttleMid", + "ctype": "uint8_t", + "desc": "Throttle Midpoint (`currentControlRateProfile->throttle.rcMid8`)", + "units": "" + }, + { + "name": "throttleExpo", + "ctype": "uint8_t", + "desc": "Throttle Expo (`currentControlRateProfile->throttle.rcExpo8`)", + "units": "" + }, + { + "name": "tpaBreakpoint", + "ctype": "uint16_t", + "desc": "Throttle PID Attenuation (TPA) breakpoint (`currentControlRateProfile->throttle.pa_breakpoint`)", + "units": "" + }, + { + "name": "rcYawExpo", + "ctype": "uint8_t", + "desc": "Yaw RC Expo (`currentControlRateProfile->stabilized.rcYawExpo8`)", + "units": "" + } + ] + }, + "notes": "Superseded by `MSP2_INAV_RATE_PROFILE` which includes manual rates/expos.", + "description": "Retrieves RC tuning parameters (rates, expos, TPA) for the current control rate profile." + }, + "MSP_ACTIVEBOXES": { + "code": 113, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "activeModes", + "ctype": "boxBitmask_t", + "desc": "Bitmask: all active modes (`packBoxModeFlags()`). Size depends on `boxBitmask_t` definition", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "notes": "Use this instead of `MSP_STATUS` or `MSP_STATUS_EX` if more than 32 modes are possible.", + "description": "Provides the full bitmask of currently active flight modes (boxes)." + }, + "MSP_MISC": { + "code": 114, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "midRc", + "ctype": "uint16_t", + "desc": "Mid RC value (`PWM_RANGE_MIDDLE`, typically 1500)", + "units": "PWM" + }, + { + "name": "legacyMinThrottle", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "maxThrottle", + "ctype": "uint16_t", + "desc": "Maximum throttle command (`getMaxThrottle()`)", + "units": "PWM" + }, + { + "name": "minCommand", + "ctype": "uint16_t", + "desc": "Minimum motor command when disarmed (`motorConfig()->mincommand`)", + "units": "PWM" + }, + { + "name": "failsafeThrottle", + "ctype": "uint16_t", + "desc": "Failsafe throttle level (`currentBatteryProfile->failsafe_throttle`)", + "units": "PWM" + }, + { + "name": "gpsType", + "ctype": "uint8_t", + "desc": "Enum `gpsProvider_e` GPS provider type (`gpsConfig()->provider`). 0 if `USE_GPS` disabled", + "units": "Enum", + "enum": "gpsProvider_e" + }, + { + "name": "legacyGpsBaud", + "ctype": "uint8_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "gpsSbasMode", + "ctype": "uint8_t", + "desc": "Enum `sbasMode_e` GPS SBAS mode (`gpsConfig()->sbasMode`). 0 if `USE_GPS` disabled", + "units": "Enum", + "enum": "sbasMode_e" + }, + { + "name": "legacyMwCurrentOut", + "ctype": "uint8_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "rssiChannel", + "ctype": "uint8_t", + "desc": "RSSI channel index (1-based) (`rxConfig()->rssi_channel`)", + "units": "Index" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Always 0", + "value": 0 + }, + { + "name": "magDeclination", + "ctype": "uint16_t", + "desc": "Magnetic declination / 10 (`compassConfig()->mag_declination / 10`). 0 if `USE_MAG` disabled", + "units": "0.1 degrees" + }, + { + "name": "vbatScale", + "ctype": "uint8_t", + "desc": "Voltage scale / 10 (`batteryMetersConfig()->voltage.scale / 10`). 0 if `USE_ADC` disabled", + "units": "Scale / 10" + }, + { + "name": "vbatMinCell", + "ctype": "uint8_t", + "desc": "Min cell voltage / 10 (`currentBatteryProfile->voltage.cellMin / 10`). 0 if `USE_ADC` disabled", + "units": "0.1V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint8_t", + "desc": "Max cell voltage / 10 (`currentBatteryProfile->voltage.cellMax / 10`). 0 if `USE_ADC` disabled", + "units": "0.1V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint8_t", + "desc": "Warning cell voltage / 10 (`currentBatteryProfile->voltage.cellWarning / 10`). 0 if `USE_ADC` disabled", + "units": "0.1V" + } + ] + }, + "notes": "Superseded by `MSP2_INAV_MISC` and other specific commands which offer better precision and more fields.", + "description": "Retrieves miscellaneous configuration settings, mostly related to RC, GPS, Mag, and Battery voltage (legacy formats)." + }, + "MSP_BOXNAMES": { + "code": 116, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "boxNamesString", + "desc": "String containing mode names separated by ';'. Null termination not guaranteed by MSP, relies on payload size. (`serializeBoxNamesReply()`)", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "The exact set of names depends on compiled features and configuration. Due to the size of the payload, it is recommended that [`MSP_BOXIDS`](#msp_boxids-119--0x77) is used instead.", + "description": "Provides a semicolon-separated string containing the names of all available flight modes (boxes)." + }, + "MSP_PIDNAMES": { + "code": 117, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "pidNamesString", + "desc": "String \"ROLL;PITCH;YAW;ALT;Pos;PosR;NavR;LEVEL;MAG;VEL;\". Null termination not guaranteed by MSP", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "", + "description": "Provides a semicolon-separated string containing the names of the PID controllers." }, - "notes": "Superseded by `MSP2_INAV_ANALOG` which provides higher precision and more fields.", - "description": "Provides analog sensor readings: battery voltage, current consumption (mAh), RSSI, and current draw (Amps)." - }, - "MSP_RC_TUNING": { - "code": 111, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "legacyRcRate", - "ctype": "uint8_t", - "desc": "Always 100 (Legacy, unused)", - "units": "", - "value": 100 - }, - { - "name": "rcExpo", - "ctype": "uint8_t", - "desc": "Roll/Pitch RC Expo (`currentControlRateProfile->stabilized.rcExpo8`)", - "units": "" - }, - { - "name": "rollRate", - "ctype": "uint8_t", - "desc": "Roll Rate (`currentControlRateProfile->stabilized.rates[FD_ROLL]`)", - "units": "" - }, - { - "name": "pitchRate", - "ctype": "uint8_t", - "desc": "Pitch Rate (`currentControlRateProfile->stabilized.rates[FD_PITCH]`)", - "units": "" - }, - { - "name": "yawRate", - "ctype": "uint8_t", - "desc": "Yaw Rate (`currentControlRateProfile->stabilized.rates[FD_YAW]`)", - "units": "" - }, - { - "name": "dynamicThrottlePID", - "ctype": "uint8_t", - "desc": "Dynamic Throttle PID (TPA) value (`currentControlRateProfile->throttle.dynPID`)", - "units": "" - }, - { - "name": "throttleMid", - "ctype": "uint8_t", - "desc": "Throttle Midpoint (`currentControlRateProfile->throttle.rcMid8`)", - "units": "" - }, - { - "name": "throttleExpo", - "ctype": "uint8_t", - "desc": "Throttle Expo (`currentControlRateProfile->throttle.rcExpo8`)", - "units": "" - }, - { - "name": "tpaBreakpoint", - "ctype": "uint16_t", - "desc": "Throttle PID Attenuation (TPA) breakpoint (`currentControlRateProfile->throttle.pa_breakpoint`)", - "units": "" - }, - { - "name": "rcYawExpo", - "ctype": "uint8_t", - "desc": "Yaw RC Expo (`currentControlRateProfile->stabilized.rcYawExpo8`)", - "units": "" - } - ] - }, - "notes": "Superseded by `MSP2_INAV_RATE_PROFILE` which includes manual rates/expos.", - "description": "Retrieves RC tuning parameters (rates, expos, TPA) for the current control rate profile." - }, - "MSP_ACTIVEBOXES": { - "code": 113, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "activeModes", - "ctype": "boxBitmask_t", - "desc": "Bitmask: all active modes (`packBoxModeFlags()`). Size depends on `boxBitmask_t` definition", - "units": "Bitmask", - "bitmask": true - } - ] - }, - "notes": "Use this instead of `MSP_STATUS` or `MSP_STATUS_EX` if more than 32 modes are possible.", - "description": "Provides the full bitmask of currently active flight modes (boxes)." - }, - "MSP_MISC": { - "code": 114, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "midRc", - "ctype": "uint16_t", - "desc": "Mid RC value (`PWM_RANGE_MIDDLE`, typically 1500)", - "units": "PWM" - }, - { - "name": "legacyMinThrottle", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "maxThrottle", - "ctype": "uint16_t", - "desc": "Maximum throttle command (`getMaxThrottle()`)", - "units": "PWM" - }, - { - "name": "minCommand", - "ctype": "uint16_t", - "desc": "Minimum motor command when disarmed (`motorConfig()->mincommand`)", - "units": "PWM" - }, - { - "name": "failsafeThrottle", - "ctype": "uint16_t", - "desc": "Failsafe throttle level (`currentBatteryProfile->failsafe_throttle`)", - "units": "PWM" - }, - { - "name": "gpsType", - "ctype": "uint8_t", - "desc": "Enum `gpsProvider_e` GPS provider type (`gpsConfig()->provider`). 0 if `USE_GPS` disabled", - "units": "Enum", - "enum": "gpsProvider_e" - }, - { - "name": "legacyGpsBaud", - "ctype": "uint8_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "gpsSbasMode", - "ctype": "uint8_t", - "desc": "Enum `sbasMode_e` GPS SBAS mode (`gpsConfig()->sbasMode`). 0 if `USE_GPS` disabled", - "units": "Enum", - "enum": "sbasMode_e" - }, - { - "name": "legacyMwCurrentOut", - "ctype": "uint8_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "rssiChannel", - "ctype": "uint8_t", - "desc": "RSSI channel index (1-based) (`rxConfig()->rssi_channel`)", - "units": "Index" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Always 0", - "value": 0 - }, - { - "name": "magDeclination", - "ctype": "uint16_t", - "desc": "Magnetic declination / 10 (`compassConfig()->mag_declination / 10`). 0 if `USE_MAG` disabled", - "units": "0.1 degrees" - }, - { - "name": "vbatScale", - "ctype": "uint8_t", - "desc": "Voltage scale / 10 (`batteryMetersConfig()->voltage.scale / 10`). 0 if `USE_ADC` disabled", - "units": "Scale / 10" - }, - { - "name": "vbatMinCell", - "ctype": "uint8_t", - "desc": "Min cell voltage / 10 (`currentBatteryProfile->voltage.cellMin / 10`). 0 if `USE_ADC` disabled", - "units": "0.1V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint8_t", - "desc": "Max cell voltage / 10 (`currentBatteryProfile->voltage.cellMax / 10`). 0 if `USE_ADC` disabled", - "units": "0.1V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint8_t", - "desc": "Warning cell voltage / 10 (`currentBatteryProfile->voltage.cellWarning / 10`). 0 if `USE_ADC` disabled", - "units": "0.1V" - } - ] - }, - "notes": "Superseded by `MSP2_INAV_MISC` and other specific commands which offer better precision and more fields.", - "description": "Retrieves miscellaneous configuration settings, mostly related to RC, GPS, Mag, and Battery voltage (legacy formats)." - }, - "MSP_BOXNAMES": { - "code": 116, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "boxNamesString", - "desc": "String containing mode names separated by ';'. Null termination not guaranteed by MSP, relies on payload size. (`serializeBoxNamesReply()`)", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "The exact set of names depends on compiled features and configuration. Due to the size of the payload, it is recommended that [`MSP_BOXIDS`](#msp_boxids-119--0x77) is used instead.", - "description": "Provides a semicolon-separated string containing the names of all available flight modes (boxes)." - }, - "MSP_PIDNAMES": { - "code": 117, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "pidNamesString", - "desc": "String \"ROLL;PITCH;YAW;ALT;Pos;PosR;NavR;LEVEL;MAG;VEL;\". Null termination not guaranteed by MSP", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "", - "description": "Provides a semicolon-separated string containing the names of the PID controllers." - }, - "MSP_WP": { - "code": 118, - "mspv": 1, - "request": { - "payload": [ - { - "name": "waypointIndex", - "ctype": "uint8_t", - "desc": "Index of the waypoint to retrieve (0 to `NAV_MAX_WAYPOINTS - 1`)", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "waypointIndex", - "ctype": "uint8_t", - "desc": "Index of the returned waypoint", - "units": "Index" - }, - { - "name": "action", - "ctype": "uint8_t", - "desc": "Enum `navWaypointActions_e` Waypoint action type", - "units": "Enum", - "enum": "navWaypointActions_e" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude coordinate", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude coordinate", - "units": "deg * 1e7" - }, - { - "name": "altitude", - "ctype": "int32_t", - "desc": "Altitude coordinate (relative to home or sea level, see flag)", - "units": "cm" - }, - { - "name": "param1", - "ctype": "int16_t", - "desc": "Parameter 1 (meaning depends on action)", - "units": "Varies" - }, - { - "name": "param2", - "ctype": "int16_t", - "desc": "Parameter 2 (meaning depends on action)", - "units": "Varies" - }, - { - "name": "param3", - "ctype": "int16_t", - "desc": "Parameter 3 (meaning depends on action)", - "units": "Varies" - }, - { - "name": "flag", - "ctype": "uint8_t", - "desc": "Bitmask: Waypoint flags (`NAV_WP_FLAG_*`)", - "units": "Bitmask", - "bitmask": true - } - ] - }, - "notes": "See `navWaypoint_t` and `navWaypointActions_e`.", - "description": "Get/Set a single waypoint from the mission plan." - }, - "MSP_BOXIDS": { - "code": 119, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "boxIds", - "desc": "Array of permanent IDs for each configured box (`serializeBoxReply()`). Length depends on number of boxes", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "Useful for mapping mode range configurations (`MSP_MODE_RANGES`) back to user-understandable modes via `MSP_BOXNAMES`.", - "description": "Provides a list of permanent IDs associated with the available flight modes (boxes)." - }, - "MSP_SERVO_CONFIGURATIONS": { - "code": 120, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "min", - "ctype": "int16_t", - "desc": "Minimum servo endpoint (`servoParams(i)->min`)", - "units": "PWM" - }, - { - "name": "max", - "ctype": "int16_t", - "desc": "Maximum servo endpoint (`servoParams(i)->max`)", - "units": "PWM" - }, - { - "name": "middle", - "ctype": "int16_t", - "desc": "Middle/Neutral servo position (`servoParams(i)->middle`)", - "units": "PWM" - }, - { - "name": "rate", - "ctype": "int8_t", - "desc": "Servo rate/scaling (`servoParams(i)->rate`, -125..125). Encoded as two's complement", - "units": "% (-100 to 100)" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Always 0", - "value": 0 - }, - { - "name": "reserved2", - "ctype": "uint8_t", - "desc": "Always 0", - "value": 0 - }, - { - "name": "legacyForwardChan", - "ctype": "uint8_t", - "desc": "Always 255 (Legacy)", - "value": 255 - }, - { - "name": "legacyReversedSources", - "ctype": "uint32_t", - "desc": "Always 0 (Legacy)", - "value": 0 - } - ], - "repeating": "MAX_SUPPORTED_SERVOS" - }, - "variable_len": "MAX_SUPPORTED_SERVOS", - "notes": "Superseded by `MSP2_INAV_SERVO_CONFIG` which has a cleaner structure.", - "description": "Retrieves the configuration parameters for all supported servos (min, max, middle, rate). Legacy format with unused fields." - }, - "MSP_NAV_STATUS": { - "code": 121, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "navMode", - "ctype": "uint8_t", - "desc": "Enum (`navSystemStatus_Mode_e`): Current navigation mode (None, RTH, NAV, Hold, etc.) (`NAV_Status.mode`)", - "units": "", - "enum": "navSystemStatus_Mode_e" - }, - { - "name": "navState", - "ctype": "uint8_t", - "desc": "Enum (`navSystemStatus_State_e`): Current navigation state (`NAV_Status.state`)", - "units": "", - "enum": "navSystemStatus_State_e" - }, - { - "name": "activeWpAction", - "ctype": "uint8_t", - "desc": "Enum (`navWaypointActions_e`): Action of the currently executing waypoint (`NAV_Status.activeWpAction`)", - "units": "", - "enum": "navWaypointActions_e" - }, - { - "name": "activeWpNumber", - "ctype": "uint8_t", - "desc": "Index: Index of the currently executing waypoint (`NAV_Status.activeWpNumber`)", - "units": "" - }, - { - "name": "navError", - "ctype": "uint8_t", - "desc": "Enum (`navSystemStatus_Error_e`): Current navigation error code (`NAV_Status.error`)", - "units": "", - "enum": "navSystemStatus_Error_e" - }, - { - "name": "targetHeading", - "ctype": "int16_t", - "desc": "Target heading for heading controller (`getHeadingHoldTarget()`)", - "units": "degrees" - } - ] - }, - "notes": "Requires `USE_GPS`.", - "description": "Retrieves the current status of the navigation system." - }, - "MSP_NAV_CONFIG": { - "code": 122, - "mspv": 1, - "not_implemented": true - }, - "MSP_3D": { - "code": 124, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "deadbandLow", - "ctype": "uint16_t", - "desc": "Lower deadband limit for 3D mode (`reversibleMotorsConfig()->deadband_low`)", - "units": "PWM" - }, - { - "name": "deadbandHigh", - "ctype": "uint16_t", - "desc": "Upper deadband limit for 3D mode (`reversibleMotorsConfig()->deadband_high`)", - "units": "PWM" - }, - { - "name": "neutral", - "ctype": "uint16_t", - "desc": "Neutral throttle point for 3D mode (`reversibleMotorsConfig()->neutral`)", - "units": "PWM" - } - ] - }, - "notes": "Requires reversible motor support.", - "description": "Retrieves settings related to 3D/reversible motor operation." - }, - "MSP_RC_DEADBAND": { - "code": 125, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "deadband", - "ctype": "uint8_t", - "desc": "General RC deadband for Roll/Pitch (`rcControlsConfig()->deadband`)", - "units": "PWM" - }, - { - "name": "yawDeadband", - "ctype": "uint8_t", - "desc": "Specific deadband for Yaw (`rcControlsConfig()->yaw_deadband`)", - "units": "PWM" - }, - { - "name": "altHoldDeadband", - "ctype": "uint8_t", - "desc": "Deadband for altitude hold adjustments (`rcControlsConfig()->alt_hold_deadband`)", - "units": "PWM" - }, - { - "name": "throttleDeadband", - "ctype": "uint16_t", - "desc": "Deadband around throttle mid-stick (`rcControlsConfig()->mid_throttle_deadband`)", - "units": "PWM" - } - ] - }, - "notes": "", - "description": "Retrieves RC input deadband settings." - }, - "MSP_SENSOR_ALIGNMENT": { - "code": 126, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "gyroAlign", - "ctype": "uint8_t", - "desc": "Always 0 (Legacy alignment enum)", - "units": "", - "value": 0 - }, - { - "name": "accAlign", - "ctype": "uint8_t", - "desc": "Always 0 (Legacy alignment enum)", - "units": "", - "value": 0 - }, - { - "name": "magAlign", - "ctype": "uint8_t", - "desc": "Magnetometer alignment (`compassConfig()->mag_align`). 0 if `USE_MAG` disabled", - "units": "" - }, - { - "name": "opflowAlign", - "ctype": "uint8_t", - "desc": "Optical flow alignment (`opticalFlowConfig()->opflow_align`). 0 if `USE_OPFLOW` disabled", - "units": "" - } - ] - }, - "notes": "Board alignment is now typically handled by `MSP_BOARD_ALIGNMENT`. This returns legacy enum values where applicable.", - "description": "Retrieves sensor alignment settings (legacy format)." - }, - "MSP_LED_STRIP_MODECOLOR": { - "code": 127, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "modeIndex", - "ctype": "uint8_t", - "desc": "Index of the LED mode Enum (`ledModeIndex_e`). `LED_MODE_COUNT` for special colors", - "units": "", - "enum": "ledModeIndex_e" - }, - { - "name": "directionOrSpecialIndex", - "ctype": "uint8_t", - "desc": "Index of the direction (`ledDirectionId_e`) or special color (`ledSpecialColorIds_e`)", - "units": "" - }, - { - "name": "colorIndex", - "ctype": "uint8_t", - "desc": "Index of the color assigned from `ledStripConfig()->colors`", - "units": "" - } - ], - "repeating": "LED_MODE_COUNT * LED_DIRECTION_COUNT + LED_SPECIAL_COLOR_COUNT" - }, - "variable_len": "LED_MODE_COUNT * LED_DIRECTION_COUNT + LED_SPECIAL_COLOR_COUNT", - "notes": "Only available if `USE_LED_STRIP` is defined. Entries where `modeIndex == LED_MODE_COUNT` describe special colors.", - "description": "Retrieves the color index assigned to each LED mode and function/direction combination, including special colors." - }, - "MSP_BATTERY_STATE": { - "code": 130, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "cellCount", - "ctype": "uint8_t", - "desc": "Number of battery cells (`getBatteryCellCount()`)", - "units": "Count" - }, - { - "name": "capacity", - "ctype": "uint16_t", - "desc": "Battery capacity (`currentBatteryProfile->capacity.value`)", - "units": "mAh" - }, - { - "name": "vbatScaled", - "ctype": "uint8_t", - "desc": "Battery voltage / 10 (`getBatteryVoltage() / 10`)", - "units": "0.1V" - }, - { - "name": "mAhDrawn", - "ctype": "uint16_t", - "desc": "Consumed capacity (`getMAhDrawn()`)", - "units": "mAh" - }, - { - "name": "amperage", - "ctype": "int16_t", - "desc": "Current draw (`getAmperage()`)", - "units": "0.01A" - }, - { - "name": "batteryState", - "ctype": "uint8_t", - "desc": "Enum `batteryState_e` Current battery state (`getBatteryState()`, see `BATTERY_STATE_*`)", - "units": "Enum", - "enum": "batteryState_e" - }, - { - "name": "vbatActual", - "ctype": "uint16_t", - "desc": "Actual battery voltage (`getBatteryVoltage()`)", - "units": "0.01V" - } - ] - }, - "notes": "Only available if `USE_DJI_HD_OSD` or `USE_MSP_DISPLAYPORT` is defined. Some values are duplicated from `MSP_ANALOG` / `MSP2_INAV_ANALOG` but potentially with different scaling/types.", - "description": "Provides battery state information, formatted primarily for DJI FPV Goggles compatibility." - }, - "MSP_VTXTABLE_BAND": { - "code": 137, - "mspv": 1, - "request": null, - "reply": null, - "notes": "The ID is defined, but no handler exists in the provided C code. Likely intended to query band names and frequencies.", - "description": "Retrieves information about a specific VTX band from the VTX table. (Implementation missing in provided `fc_msp.c`)" - }, - "MSP_VTXTABLE_POWERLEVEL": { - "code": 138, - "mspv": 1, - "request": { - "payload": [ - { - "name": "powerLevelIndex", - "ctype": "uint8_t", - "desc": "1-based index of the power level to query", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "powerLevelIndex", - "ctype": "uint8_t", - "desc": "1-based index of the returned power level", - "units": "" - }, - { - "name": "powerValue", - "ctype": "uint16_t", - "desc": "Always 0 (Actual power value in mW is not stored/returned via MSP)", - "units": "", - "value": 0 - }, - { - "name": "labelLength", - "ctype": "uint8_t", - "desc": "Length of the power level label string that follows", - "units": "" - }, - { - "name": "label", - "desc": "Power level label string (e.g., \"25\", \"200\"). Length given by previous field", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "Requires `USE_VTX_CONTROL`. Returns error if index is out of bounds. The `powerValue` field is unused.", - "description": "Retrieves information about a specific VTX power level from the VTX table." - }, - "MSP_STATUS_EX": { - "code": 150, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "cycleTime", - "ctype": "uint16_t", - "desc": "Main loop cycle time", - "units": "Β΅s" - }, - { - "name": "i2cErrors", - "ctype": "uint16_t", - "desc": "I2C errors", - "units": "Count" - }, - { - "name": "sensorStatus", - "ctype": "uint16_t", - "desc": "Bitmask: Sensor status", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "activeModesLow", - "ctype": "uint32_t", - "desc": "Bitmask: First 32 active modes", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "profile", - "ctype": "uint8_t", - "desc": "Current config profile index", - "units": "Index" - }, - { - "name": "cpuLoad", - "ctype": "uint16_t", - "desc": "Average system load percentage (`averageSystemLoadPercent`)", - "units": "%" - }, - { - "name": "armingFlags", - "ctype": "uint16_t", - "desc": "Bitmask: Flight controller arming flags (`armingFlags`). Note: Truncated to 16 bits", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "accCalibAxisFlags", - "ctype": "uint8_t", - "desc": "Bitmask: Accelerometer calibrated axes flags (`accGetCalibrationAxisFlags()`)", - "units": "Bitmask", - "bitmask": true - } - ] - }, - "notes": "Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements.", - "description": "Provides extended flight controller status, including CPU load, arming flags, and calibration status, in addition to `MSP_STATUS` fields." - }, - "MSP_SENSOR_STATUS": { - "code": 151, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "overallHealth", - "ctype": "uint8_t", - "desc": "1 if all essential hardware is healthy, 0 otherwise (`isHardwareHealthy()`)", - "units": "Boolean" - }, - { - "name": "gyroStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Gyro hardware status (`getHwGyroStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "accStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Accelerometer hardware status (`getHwAccelerometerStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "magStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Compass hardware status (`getHwCompassStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "baroStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Barometer hardware status (`getHwBarometerStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "gpsStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` GPS hardware status (`getHwGPSStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "rangefinderStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Rangefinder hardware status (`getHwRangefinderStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "pitotStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Pitot hardware status (`getHwPitotmeterStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - }, - { - "name": "opflowStatus", - "ctype": "uint8_t", - "desc": "Enum `hardwareSensorStatus_e` Optical Flow hardware status (`getHwOpticalFlowStatus()`)", - "units": "Enum", - "enum": "hardwareSensorStatus_e" - } - ] - }, - "notes": "Status values map to the `hardwareSensorStatus_e` enum: `HW_SENSOR_NONE`, `HW_SENSOR_OK`, `HW_SENSOR_UNAVAILABLE`, `HW_SENSOR_UNHEALTHY`.", - "description": "Provides the hardware status for each individual sensor system." - }, - "MSP_UID": { - "code": 160, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "uid0", - "ctype": "uint32_t", - "desc": "First 32 bits of the unique ID (`U_ID_0`)", - "units": "" - }, - { - "name": "uid1", - "ctype": "uint32_t", - "desc": "Middle 32 bits of the unique ID (`U_ID_1`)", - "units": "" - }, - { - "name": "uid2", - "ctype": "uint32_t", - "desc": "Last 32 bits of the unique ID (`U_ID_2`)", - "units": "" - } - ] - }, - "notes": "Total 12 bytes, representing a 96-bit unique ID.", - "description": "Provides the unique identifier of the microcontroller." - }, - "MSP_GPSSVINFO": { - "code": 164, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "protocolVersion", - "ctype": "uint8_t", - "desc": "Always 1 (Stub version)", - "units": "", - "value": 1 - }, - { - "name": "numChannels", - "ctype": "uint8_t", - "desc": "Always 0 (Number of SV info channels reported)", - "units": "", - "value": 0 - }, - { - "name": "hdopHundredsDigit", - "ctype": "uint8_t", - "desc": "Hundreds digit of HDOP (stub always writes 0)", - "units": "" - }, - { - "name": "hdopTensDigit", - "ctype": "uint8_t", - "desc": "Tens digit of HDOP (`gpsSol.hdop / 100`, truncated)", - "units": "" - }, - { - "name": "hdopUnitsDigit", - "ctype": "uint8_t", - "desc": "Units digit of HDOP (`gpsSol.hdop / 100`, duplicated by stub)", - "units": "" - } - ] - }, - "notes": "Requires `USE_GPS`. This is just a stub in INAV and does not provide actual per-satellite signal info. HDOP digits are not formatted correctly: tens and units both contain `gpsSol.hdop / 100`.", - "description": "Provides satellite signal strength information (legacy U-Blox compatibility stub)." - }, - "MSP_GPSSTATISTICS": { - "code": 166, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "lastMessageDt", - "ctype": "uint16_t", - "desc": "Time since last valid GPS message (`gpsStats.lastMessageDt`)", - "units": "ms" - }, - { - "name": "errors", - "ctype": "uint32_t", - "desc": "Number of GPS communication errors (`gpsStats.errors`)", - "units": "Count" - }, - { - "name": "timeouts", - "ctype": "uint32_t", - "desc": "Number of GPS communication timeouts (`gpsStats.timeouts`)", - "units": "Count" - }, - { - "name": "packetCount", - "ctype": "uint32_t", - "desc": "Number of valid GPS packets received (`gpsStats.packetCount`)", - "units": "Count" - }, - { - "name": "hdop", - "ctype": "uint16_t", - "desc": "Horizontal Dilution of Precision (`gpsSol.hdop`)", - "units": "HDOP * 100" - }, - { - "name": "eph", - "ctype": "uint16_t", - "desc": "Estimated Horizontal Position Accuracy (`gpsSol.eph`)", - "units": "cm" - }, - { - "name": "epv", - "ctype": "uint16_t", - "desc": "Estimated Vertical Position Accuracy (`gpsSol.epv`)", - "units": "cm" - } - ] - }, - "notes": "Requires `USE_GPS`.", - "description": "Provides debugging statistics for the GPS communication link." - }, - "MSP_OSD_VIDEO_CONFIG": { - "code": 180, - "mspv": 1, - "request": null, - "reply": null, - "name": "MSP_OSD_VIDEO_CONFIG", - "missing": true - }, - "MSP_SET_OSD_VIDEO_CONFIG": { - "code": 181, - "mspv": 1, - "request": null, - "reply": null, - "name": "MSP_SET_OSD_VIDEO_CONFIG", - "missing": true - }, - "MSP_DISPLAYPORT": { - "code": 182, - "mspv": 1, - "request": null, - "reply": null, - "name": "MSP_DISPLAYPORT", - "missing": true - }, - "MSP_SET_TX_INFO": { - "code": 186, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rssi", - "ctype": "uint8_t", - "desc": "RSSI value (0-255) provided by the external source; firmware scales it to 10-bit (`value << 2`)", - "units": "Raw" - } - ] - }, - "reply": null, - "notes": "Calls `setRSSIFromMSP()`. Expects 1 byte.", - "description": "Allows a transmitter LUA script (or similar) to send runtime information (currently only RSSI) to the firmware." - }, - "MSP_TX_INFO": { - "code": 187, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "rssiSource", - "ctype": "uint8_t", - "desc": "Enum: Source of the RSSI value (`getRSSISource()`, see `rssiSource_e`)", - "units": "", - "enum": "rssiSource_e" - }, - { - "name": "rtcDateTimeIsSet", - "ctype": "uint8_t", - "desc": "Boolean: 1 if the RTC has been set, 0 otherwise", - "units": "" - } - ] - }, - "notes": "See `rssiSource_e`.", - "description": "Provides information potentially useful for transmitter LUA scripts." - }, - "MSP_SET_RAW_RC": { - "code": 200, - "mspv": 1, - "request": { - "payload": [ - { - "name": "rcChannels", - "desc": "Array of RC channel values (typically 1000-2000). Number of channels determined by payload size", - "ctype": "uint16_t", - "array": true, - "array_size": 0, - "units": "PWM" - } - ] - }, - "reply": null, - "variable_len": true, - "notes": "Requires `USE_RX_MSP`. Maximum channels `MAX_SUPPORTED_RC_CHANNEL_COUNT`. Calls `rxMspFrameReceive()`.", - "description": "Provides raw RC channel data to the flight controller, typically used when the receiver is connected via MSP (e.g., MSP RX feature)." - }, - "MSP_SET_RAW_GPS": { - "code": 201, - "mspv": 1, - "request": { - "payload": [ - { - "name": "fixType", - "ctype": "uint8_t", - "desc": "Enum `gpsFixType_e` GPS fix type", - "units": "Enum", - "enum": "gpsFixType_e" - }, - { - "name": "numSat", - "ctype": "uint8_t", - "desc": "Number of satellites", - "units": "Count" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude", - "units": "deg * 1e7" - }, - { - "name": "altitude", - "ctype": "uint16_t", - "desc": "Altitude in meters (converted to centimeters internally; limited to 0-65535 m)", - "units": "m" - }, - { - "name": "speed", - "ctype": "uint16_t", - "desc": "Ground speed (`gpsSol.groundSpeed`)", - "units": "cm/s" - } - ] - }, - "reply": null, - "notes": "Requires `USE_GPS`. Expects 14 bytes. Updates `gpsSol` structure and calls `onNewGPSData()`. Note the altitude unit mismatch (meters in MSP, cm internal). Does not provide velocity components.", - "description": "Provides raw GPS data to the flight controller, typically for simulation or external GPS injection." - }, - "MSP_SET_BOX": { - "code": 203, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`. Mode changes are typically handled via RC channels (`MSP_MODE_RANGES`).", - "description": "Sets the state of flight modes (boxes). (Likely unused/obsolete in INAV)." - }, - "MSP_SET_RC_TUNING": { - "code": 204, - "mspv": 1, - "request": { - "payload": [ - { - "name": "legacyRcRate", - "ctype": "uint8_t", - "desc": "Ignored", - "units": "" - }, - { - "name": "rcExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rcExpo8`", - "units": "" - }, - { - "name": "rollRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_ROLL]` (constrained)", - "units": "" - }, - { - "name": "pitchRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_PITCH]` (constrained)", - "units": "" - }, - { - "name": "yawRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_YAW]` (constrained)", - "units": "" - }, - { - "name": "dynamicThrottlePID", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->throttle.dynPID` (constrained)", - "units": "" - }, - { - "name": "throttleMid", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->throttle.rcMid8`", - "units": "" - }, - { - "name": "throttleExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->throttle.rcExpo8`", - "units": "" - }, - { - "name": "tpaBreakpoint", - "ctype": "uint16_t", - "desc": "Sets `currentControlRateProfile->throttle.pa_breakpoint`", - "units": "" - }, - { - "name": "rcYawExpo", - "ctype": "uint8_t", - "desc": "(Optional) Sets `currentControlRateProfile->stabilized.rcYawExpo8`", - "units": "", - "optional": true - } - ] - }, - "reply": null, - "notes": "Expects 10 or 11 bytes. Calls `schedulePidGainsUpdate()`. Superseded by `MSP2_INAV_SET_RATE_PROFILE`.", - "description": "Sets RC tuning parameters (rates, expos, TPA) for the current control rate profile." - }, - "MSP_ACC_CALIBRATION": { - "code": 205, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Will fail if armed. Calls `accStartCalibration()`.", - "description": "Starts the accelerometer calibration procedure." - }, - "MSP_MAG_CALIBRATION": { - "code": 206, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Will fail if armed. Enables the `CALIBRATE_MAG` state flag.", - "description": "Starts the magnetometer calibration procedure." - }, - "MSP_SET_MISC": { - "code": 207, - "mspv": 1, - "request": { - "payload": [ - { - "name": "midRc", - "ctype": "uint16_t", - "desc": "Ignored", - "units": "PWM" - }, - { - "name": "legacyMinThrottle", - "ctype": "uint16_t", - "desc": "Ignored" - }, - { - "name": "legacyMaxThrottle", - "ctype": "uint16_t", - "desc": "Ignored" - }, - { - "name": "minCommand", - "ctype": "uint16_t", - "desc": "Sets `motorConfigMutable()->mincommand` (constrained 0-PWM_RANGE_MAX)", - "units": "PWM" - }, - { - "name": "failsafeThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->failsafe_throttle` (constrained PWM_RANGE_MIN/MAX)", - "units": "PWM" - }, - { - "name": "gpsType", - "ctype": "uint8_t", - "desc": "Enum `gpsProvider_e` (Sets `gpsConfigMutable()->provider`)", - "units": "Enum", - "enum": "gpsProvider_e" - }, - { - "name": "legacyGpsBaud", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "gpsSbasMode", - "ctype": "uint8_t", - "desc": "Enum `sbasMode_e` (Sets `gpsConfigMutable()->sbasMode`)", - "units": "Enum", - "enum": "sbasMode_e" - }, - { - "name": "legacyMwCurrentOut", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "rssiChannel", - "ctype": "uint8_t", - "desc": "Sets `rxConfigMutable()->rssi_channel` (constrained 0-MAX_SUPPORTED_RC_CHANNEL_COUNT). Updates source", - "units": "Index" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "magDeclination", - "ctype": "uint16_t", - "desc": "Sets `compassConfigMutable()->mag_declination = value * 10` (if `USE_MAG`)", - "units": "0.1 degrees" - }, - { - "name": "vbatScale", - "ctype": "uint8_t", - "desc": "Sets `batteryMetersConfigMutable()->voltage.scale = value * 10` (if `USE_ADC`)", - "units": "Scale / 10" - }, - { - "name": "vbatMinCell", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin = value * 10` (if `USE_ADC`)", - "units": "0.1V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax = value * 10` (if `USE_ADC`)", - "units": "0.1V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning = value * 10` (if `USE_ADC`)", - "units": "0.1V" - } - ] - }, - "reply": null, - "notes": "Expects 22 bytes. Superseded by `MSP2_INAV_SET_MISC`.", - "description": "Sets miscellaneous configuration settings (legacy formats/scaling)." - }, - "MSP_RESET_CONF": { - "code": 208, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Will fail if armed. Suspends RX, calls `resetEEPROM()`, `writeEEPROM()`, `readEEPROM()`, resumes RX. Use with caution!", - "description": "Resets all configuration settings to their default values and saves to EEPROM." - }, - "MSP_SET_WP": { - "code": 209, - "mspv": 1, - "request": { - "payload": [ - { - "name": "waypointIndex", - "ctype": "uint8_t", - "desc": "Index of the waypoint to set (0 to `NAV_MAX_WAYPOINTS - 1`)", - "units": "Index" - }, - { - "name": "action", - "ctype": "uint8_t", - "desc": "Enum `navWaypointActions_e` Waypoint action type", - "units": "Enum", - "enum": "navWaypointActions_e" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude coordinate", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude coordinate", - "units": "deg * 1e7" - }, - { - "name": "altitude", - "ctype": "int32_t", - "desc": "Altitude coordinate", - "units": "cm" - }, - { - "name": "param1", - "ctype": "uint16_t", - "desc": "Parameter 1", - "units": "Varies" - }, - { - "name": "param2", - "ctype": "uint16_t", - "desc": "Parameter 2", - "units": "Varies" - }, - { - "name": "param3", - "ctype": "uint16_t", - "desc": "Parameter 3", - "units": "Varies" - }, - { - "name": "flag", - "ctype": "uint8_t", - "desc": "Bitmask: Waypoint flags (`navWaypointFlags_e`)", - "units": "Bitmask", - "bitmask": true, - "enum": "navWaypointFlags_e" - } - ] - }, - "reply": null, - "notes": "Expects 21 bytes. Calls `setWaypoint()`. If `USE_FW_AUTOLAND` is enabled, this also interacts with autoland approach settings based on waypoint index and flags.", - "description": "Sets a single waypoint in the mission plan." - }, - "MSP_SELECT_SETTING": { - "code": 210, - "mspv": 1, - "request": { - "payload": [ - { - "name": "profileIndex", - "ctype": "uint8_t", - "desc": "Index of the profile to activate (0-based)", - "units": "" - } - ] - }, - "reply": null, - "notes": "Will fail if armed. Calls `setConfigProfileAndWriteEEPROM()`.", - "description": "Selects the active configuration profile and saves it." - }, - "MSP_SET_HEAD": { - "code": 211, - "mspv": 1, - "request": { - "payload": [ - { - "name": "heading", - "ctype": "uint16_t", - "desc": "Target heading (0-359)", - "units": "degrees" - } - ] - }, - "reply": null, - "notes": "Expects 2 bytes. Calls `updateHeadingHoldTarget()`.", - "description": "Sets the target heading for the heading hold controller (e.g., during MAG mode)." - }, - "MSP_SET_SERVO_CONFIGURATION": { - "code": 212, - "mspv": 1, - "request": { - "payload": [ - { - "name": "servoIndex", - "ctype": "uint8_t", - "desc": "Index of the servo to configure (0 to `MAX_SUPPORTED_SERVOS - 1`)", - "units": "Index" - }, - { - "name": "min", - "ctype": "uint16_t", - "desc": "Minimum servo endpoint", - "units": "PWM" - }, - { - "name": "max", - "ctype": "uint16_t", - "desc": "Maximum servo endpoint", - "units": "PWM" - }, - { - "name": "middle", - "ctype": "uint16_t", - "desc": "Middle/Neutral servo position", - "units": "PWM" - }, - { - "name": "rate", - "ctype": "uint8_t", - "desc": "Servo rate/scaling", - "units": "%" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "reserved2", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "legacyForwardChan", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "legacyReversedSources", - "ctype": "uint32_t", - "desc": "Ignored" - } - ] - }, - "reply": null, - "notes": "Expects 15 bytes. Returns error if index is invalid. Calls `servoComputeScalingFactors()`. Superseded by `MSP2_INAV_SET_SERVO_CONFIG`.", - "description": "Sets the configuration for a single servo (legacy format)." - }, - "MSP_SET_MOTOR": { - "code": 214, - "mspv": 1, - "request": { - "payload": [ - { - "name": "motorValues", - "desc": "Array of motor values to set when disarmed. Only affects first `MAX_SUPPORTED_MOTORS` entries", - "ctype": "uint16_t", - "array": true, - "array_size": 8, - "units": "PWM" - } - ] - }, - "reply": null, - "notes": "Expects 16 bytes. Modifies the `motor_disarmed` array. These values are *not* saved persistently.", - "description": "Sets the disarmed motor values, typically used for motor testing or propeller balancing functions in a configurator." - }, - "MSP_SET_NAV_CONFIG": { - "code": 215, - "mspv": 1, - "not_implemented": true - }, - "MSP_SET_3D": { - "code": 217, - "mspv": 1, - "request": { - "payload": [ - { - "name": "deadbandLow", - "ctype": "uint16_t", - "desc": "Sets `reversibleMotorsConfigMutable()->deadband_low`", - "units": "PWM" - }, - { - "name": "deadbandHigh", - "ctype": "uint16_t", - "desc": "Sets `reversibleMotorsConfigMutable()->deadband_high`", - "units": "PWM" - }, - { - "name": "neutral", - "ctype": "uint16_t", - "desc": "Sets `reversibleMotorsConfigMutable()->neutral`", - "units": "PWM" - } - ] - }, - "reply": null, - "notes": "Expects 6 bytes. Requires reversible motor support.", - "description": "Sets parameters related to 3D/reversible motor operation." - }, - "MSP_SET_RC_DEADBAND": { - "code": 218, - "mspv": 1, - "request": { - "payload": [ - { - "name": "deadband", - "ctype": "uint8_t", - "desc": "Sets `rcControlsConfigMutable()->deadband`", - "units": "PWM" - }, - { - "name": "yawDeadband", - "ctype": "uint8_t", - "desc": "Sets `rcControlsConfigMutable()->yaw_deadband`", - "units": "PWM" - }, - { - "name": "altHoldDeadband", - "ctype": "uint8_t", - "desc": "Sets `rcControlsConfigMutable()->alt_hold_deadband`", - "units": "PWM" - }, - { - "name": "throttleDeadband", - "ctype": "uint16_t", - "desc": "Sets `rcControlsConfigMutable()->mid_throttle_deadband`", - "units": "PWM" - } - ] - }, - "reply": null, - "notes": "Expects 5 bytes.", - "description": "Sets RC input deadband values." - }, - "MSP_SET_RESET_CURR_PID": { - "code": 219, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Calls `PG_RESET_CURRENT(pidProfile)`. To save, follow with `MSP_EEPROM_WRITE`.", - "description": "Resets the PIDs of the *current* profile to their default values. Does not save." - }, - "MSP_SET_SENSOR_ALIGNMENT": { - "code": 220, - "mspv": 1, - "request": { - "payload": [ - { - "name": "gyroAlign", - "ctype": "uint8_t", - "desc": "Ignored", - "units": "" - }, - { - "name": "accAlign", - "ctype": "uint8_t", - "desc": "Ignored", - "units": "" - }, - { - "name": "magAlign", - "ctype": "uint8_t", - "desc": "Sets `compassConfigMutable()->mag_align` (if `USE_MAG`)", - "units": "" - }, - { - "name": "opflowAlign", - "ctype": "uint8_t", - "desc": "Sets `opticalFlowConfigMutable()->opflow_align` (if `USE_OPFLOW`)", - "units": "" - } - ] - }, - "reply": null, - "notes": "Expects 4 bytes. Use `MSP_SET_BOARD_ALIGNMENT` for primary board orientation.", - "description": "Sets sensor alignment (legacy format)." - }, - "MSP_SET_LED_STRIP_MODECOLOR": { - "code": 221, - "mspv": 1, - "request": { - "payload": [ - { - "name": "modeIndex", - "ctype": "uint8_t", - "desc": "Index of the LED mode (`ledModeIndex_e` or `LED_MODE_COUNT` for special)", - "units": "" - }, - { - "name": "directionOrSpecialIndex", - "ctype": "uint8_t", - "desc": "Index of the direction (`ledDirectionId_e`) or special color (`ledSpecialColorIds_e`)", - "units": "" - }, - { - "name": "colorIndex", - "ctype": "uint8_t", - "desc": "Index of the color to assign from `ledStripConfig()->colors`", - "units": "" - } - ] - }, - "reply": null, - "notes": "Only available if `USE_LED_STRIP` is defined. Expects 3 bytes. Returns error if setting fails (invalid index).", - "description": "Sets the color index for a specific LED mode/function combination." - }, - "MSP_SET_ACC_TRIM": { - "code": 239, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`. Use `MSP_ACC_CALIBRATION`.", - "description": "Sets the accelerometer trim values (leveling calibration)." - }, - "MSP_ACC_TRIM": { - "code": 240, - "mspv": 1, - "not_implemented": true, - "request": null, - "reply": null, - "notes": "Not implemented in INAV `fc_msp.c`. Calibration data via `MSP_CALIBRATION_DATA`.", - "description": "Gets the accelerometer trim values." - }, - "MSP_SERVO_MIX_RULES": { - "code": 241, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "targetChannel", - "ctype": "uint8_t", - "desc": "Servo output channel index (0-based)", - "units": "Index" - }, - { - "name": "inputSource", - "ctype": "uint8_t", - "desc": "Enum `inputSource_e` Input source for the mix (RC chan, Roll, Pitch...)", - "units": "Enum", - "enum": "inputSource_e" - }, - { - "name": "rate", - "ctype": "int16_t", - "desc": "Mixing rate/weight (`-1000` to `+1000`, percent with sign)", - "units": "%" - }, - { - "name": "speed", - "ctype": "uint8_t", - "desc": "Speed/Slew rate limit (`0`=instant, higher slows response)", - "units": "0-255" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Always 0", - "value": 0 - }, - { - "name": "legacyMax", - "ctype": "uint8_t", - "desc": "Always 100 (Legacy)", - "value": 100 - }, - { - "name": "legacyBox", - "ctype": "uint8_t", - "desc": "Always 0 (Legacy)", - "value": 0 - } - ], - "repeating": "MAX_SERVO_RULES" - }, - "variable_len": "MAX_SERVO_RULES", - "notes": "Superseded by `MSP2_INAV_SERVO_MIXER`.", - "description": "Retrieves the custom servo mixer rules (legacy format)." - }, - "MSP_SET_SERVO_MIX_RULE": { - "code": 242, - "mspv": 1, - "request": { - "payload": [ - { - "name": "ruleIndex", - "ctype": "uint8_t", - "desc": "Index of the rule to set (0 to `MAX_SERVO_RULES - 1`)", - "units": "Index" - }, - { - "name": "targetChannel", - "ctype": "uint8_t", - "desc": "Servo output channel index", - "units": "Index" - }, - { - "name": "inputSource", - "ctype": "uint8_t", - "desc": "Enum `inputSource_e` Input source for the mix", - "units": "Enum", - "enum": "inputSource_e" - }, - { - "name": "rate", - "ctype": "int16_t", - "desc": "Mixing rate/weight (`-1000` to `+1000`, percent with sign)", - "units": "%" - }, - { - "name": "speed", - "ctype": "uint8_t", - "desc": "Speed/Slew rate limit (`0`=instant, higher slows response)", - "units": "0-255" - }, - { - "name": "legacyMinMax", - "ctype": "uint16_t", - "desc": "Ignored" - }, - { - "name": "legacyBox", - "ctype": "uint8_t", - "desc": "Ignored" - } - ] - }, - "reply": null, - "notes": "Expects 9 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`. Superseded by `MSP2_INAV_SET_SERVO_MIXER`.", - "description": "Sets a single custom servo mixer rule (legacy format)." - }, - "MSP_SET_PASSTHROUGH": { - "code": 245, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "status", - "ctype": "uint8_t", - "desc": "1 if passthrough started successfully, 0 on error (e.g., port not found). For 4way, returns number of ESCs found", - "units": "" - } - ] - }, - "notes": "Accepts 0 bytes (defaults to ESC 4-way) or up to 2 bytes for mode/argument. If successful, sets `mspPostProcessFn` to the appropriate handler (`mspSerialPassthroughFn` or `esc4wayProcess`). This handler takes over the serial port after the reply is sent. Requires `USE_SERIAL_4WAY_BLHELI_INTERFACE` for ESC passthrough.", - "description": "Enables serial passthrough mode to peripherals like ESCs (BLHeli 4-way) or other serial devices." - }, - "MSP_RTC": { - "code": 246, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "seconds", - "ctype": "int32_t", - "desc": "Seconds since epoch (or relative time if not set). 0 if RTC time unknown", - "units": "Seconds" - }, - { - "name": "millis", - "ctype": "uint16_t", - "desc": "Millisecond part of the time. 0 if RTC time unknown", - "units": "Milliseconds" - } - ] - }, - "notes": "Requires RTC hardware/support. Returns (0, 0) if time is not available/set.", - "description": "Retrieves the current Real-Time Clock time." - }, - "MSP_SET_RTC": { - "code": 247, - "mspv": 1, - "request": { - "payload": [ - { - "name": "seconds", - "ctype": "int32_t", - "desc": "Seconds component of time to set", - "units": "Seconds" - }, - { - "name": "millis", - "ctype": "uint16_t", - "desc": "Millisecond component of time to set", - "units": "Milliseconds" - } - ] - }, - "reply": null, - "notes": "Requires RTC hardware/support. Expects 6 bytes. Uses `rtcSet()`.", - "description": "Sets the Real-Time Clock time." - }, - "MSP_EEPROM_WRITE": { - "code": 250, - "mspv": 1, - "request": null, - "reply": null, - "notes": "Will fail if armed. Suspends RX, calls `writeEEPROM()`, `readEEPROM()`, resumes RX.", - "description": "Saves the current configuration from RAM to non-volatile memory (EEPROM/Flash)." - }, - "MSP_RESERVE_1": { - "code": 251, - "mspv": 1, - "request": null, - "reply": null, - "name": "MSP_RESERVE_1", - "missing": true - }, - "MSP_RESERVE_2": { - "code": 252, - "mspv": 1, - "request": null, - "reply": null, - "name": "MSP_RESERVE_2", - "missing": true - }, - "MSP_DEBUGMSG": { - "code": 253, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "Message Text", - "desc": "Debug message text (not NUL-terminated). See [serial printf debugging](https://github.com/iNavFlight/inav/blob/master/docs/development/serial_printf_debugging.md)", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "Published via the LOG UART or shared MSP/LOG port using `mspSerialPushPort()`.", - "description": "Retrieves debug (\"serial printf\") messages from the firmware." - }, - "MSP_DEBUG": { - "code": 254, - "mspv": 1, - "request": null, - "reply": { - "payload": [ - { - "name": "debugValues", - "desc": "First 4 values from the `debug` array", - "ctype": "uint16_t", - "array": true, - "array_size": 4, - "units": "" - } - ] - }, - "notes": "Useful for developers. Values are truncated to the lower 16 bits of each `debug[]` entry. See `MSP2_INAV_DEBUG` for full 32-bit values.", - "description": "Retrieves values from the firmware's `debug[]` array (legacy 16-bit version)." - }, - "MSP_V2_FRAME": { - "code": 255, - "mspv": 1, - "request": null, - "reply": null, - "notes": "See MSPv2 documentation for the actual frame structure that follows this indicator.", - "description": "This ID is used as a *payload indicator* within an MSPv1 message structure (`$M>`) to signify that the following payload conforms to the MSPv2 format. It's not a command itself." - }, - "MSP2_COMMON_TZ": { - "code": 4097, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "tzOffsetMinutes", - "ctype": "int16_t", - "desc": "Time zone offset from UTC (`timeConfig()->tz_offset`)", - "units": "Minutes" - }, - { - "name": "tzAutoDst", - "ctype": "uint8_t", - "desc": "Automatic daylight saving time enabled (`timeConfig()->tz_automatic_dst`)", - "units": "Boolean" - } - ] - }, - "notes": "", - "description": "Gets the time zone offset configuration." - }, - "MSP2_COMMON_SET_TZ": { - "code": 4098, - "mspv": 2, - "request": null, - "reply": null, - "notes": "Accepts 2 or 3 bytes.", - "description": "Sets the time zone offset configuration.", - "variants": { - "dataSize == 2": { - "description": "dataSize == 2", - "request": { - "payload": [ - { - "name": "tz_offset", - "ctype": "int16_t", - "desc": "Timezone offset from UTC.", - "units": "minutes" - } - ] - }, - "reply": null - }, - "dataSize == 3": { - "description": "dataSize == 3", - "request": { - "payload": [ - { - "name": "tz_offset", - "ctype": "int16_t", - "desc": "Timezone offset from UTC.", - "units": "minutes" - }, - { - "name": "tz_automatic_dst", - "ctype": "uint8_t", - "desc": "Automatic DST enable (0/1).", - "units": "bool" - } - ] - }, - "reply": null - } - } - }, - "MSP2_COMMON_SETTING": { - "code": 4099, - "mspv": 2, - "request": { - "payload": [ - { - "name": "settingIdentifier", - "ctype": "Varies", - "desc": "Setting name (null-terminated string) OR index selector (`0x00` followed by `uint16_t` index)", - "polymorph": true, - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "settingValue", - "desc": "Raw byte value of the setting. Size depends on the setting's type (`settingGetValueSize()`)", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "Returns error if setting not found. Use `MSP2_COMMON_SETTING_INFO` to discover settings, types, and sizes.", - "description": "Gets the value of a specific configuration setting, identified by name or index." - }, - "MSP2_COMMON_SET_SETTING": { - "code": 4100, - "mspv": 2, - "request": { - "payload": [ - { - "name": "settingIdentifier", - "ctype": "Varies", - "desc": "Setting name (null-terminated string) OR Index (0x00 followed by `uint16_t` index)", - "polymorph": true, - "units": "" - }, - { - "name": "settingValue", - "desc": "Raw byte value to set for the setting. Size must match the setting's type", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "reply": null, - "variable_len": true, - "notes": "Performs type checking and range validation (min/max). Returns error if setting not found, value size mismatch, or value out of range. Handles different data types (`uint8`, `int16`, `float`, `string`, etc.) internally.", - "description": "Sets the value of a specific configuration setting, identified by name or index." - }, - "MSP2_COMMON_MOTOR_MIXER": { - "code": 4101, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "motorMix", - "desc": "Weights for a single motor `[throttle, roll, pitch, yaw]`, each encoded as `(mix + 2.0) * 1000` (range 0-4000)", - "ctype": "uint16_t", - "array": true, - "array_size": 4, - "units": "Scaled (0-4000)" - } - ], - "repeating": "MAX_SUPPORTED_MOTORS" - }, - "variable_len": "MAX_SUPPORTED_MOTORS", - "notes": "Scaling is `(float_weight + 2.0) * 1000`. `primaryMotorMixer()` provides the data. If multiple mixer profiles are enabled (`MAX_MIXER_PROFILE_COUNT > 1`), an additional block of mixes for the next profile follows immediately.", - "description": "Retrieves the current motor mixer configuration (throttle, roll, pitch, yaw weights) for each motor." - }, - "MSP2_COMMON_SET_MOTOR_MIXER": { - "code": 4102, - "mspv": 2, - "request": { - "payload": [ - { - "name": "motorIndex", - "ctype": "uint8_t", - "desc": "Index of the motor to configure (0 to `MAX_SUPPORTED_MOTORS - 1`)", - "units": "Index" - }, - { - "name": "throttleWeight", - "ctype": "uint16_t", - "desc": "Sets throttle weight from `(value / 1000.0) - 2.0", - "units": "Scaled (0-4000)" - }, - { - "name": "rollWeight", - "ctype": "uint16_t", - "desc": "Sets roll weight from `(value / 1000.0) - 2.0", - "units": "Scaled (0-4000)" - }, - { - "name": "pitchWeight", - "ctype": "uint16_t", - "desc": "Sets pitch weight from `(value / 1000.0) - 2.0", - "units": "Scaled (0-4000)" - }, - { - "name": "yawWeight", - "ctype": "uint16_t", - "desc": "Sets yaw weight from `(value / 1000.0) - 2.0", - "units": "Scaled (0-4000)" - } - ] - }, - "reply": null, - "notes": "Expects 9 bytes. Modifies `primaryMotorMixerMutable()`. Returns error if index is invalid.", - "description": "Sets the motor mixer weights for a single motor in the primary mixer profile." - }, - "MSP2_COMMON_SETTING_INFO": { - "code": 4103, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "settingName", - "desc": "Null-terminated setting name", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - }, - { - "name": "pgn", - "ctype": "uint16_t", - "desc": "Parameter Group Number (PGN) ID", - "units": "" - }, - { - "name": "type", - "ctype": "uint8_t", - "desc": "Variable type (`VAR_UINT8`, `VAR_FLOAT`, etc.)", - "units": "" - }, - { - "name": "section", - "ctype": "uint8_t", - "desc": "Setting section (`MASTER_VALUE`, `PROFILE_VALUE`, etc.)", - "units": "" - }, - { - "name": "mode", - "ctype": "uint8_t", - "desc": "Setting mode (`MODE_NORMAL`, `MODE_LOOKUP`, etc.)", - "units": "" - }, - { - "name": "minValue", - "ctype": "int32_t", - "desc": "Minimum allowed value (as signed 32-bit)", - "units": "" - }, - { - "name": "maxValue", - "ctype": "uint32_t", - "desc": "Maximum allowed value (as unsigned 32-bit)", - "units": "" - }, - { - "name": "settingIndex", - "ctype": "uint16_t", - "desc": "Absolute index of the setting", - "units": "" - }, - { - "name": "profileIndex", - "ctype": "uint8_t", - "desc": "Current profile index (if applicable, else 0)", - "units": "" - }, - { - "name": "profileCount", - "ctype": "uint8_t", - "desc": "Total number of profiles (if applicable, else 0)", - "units": "" - }, - { - "name": "lookupNames", - "desc": "(If `mode == MODE_LOOKUP`) Series of null-terminated strings for each possible value from min to max", - "ctype": "char", - "array": true, - "array_size": 0, - "units": "" - }, - { - "name": "settingValue", - "desc": "Current raw byte value of the setting", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] - }, - "variable_len": true, - "notes": "", - "description": "Gets detailed information about a specific configuration setting (name, type, range, flags, current value, etc.)." - }, - "MSP2_COMMON_PG_LIST": { - "code": 4104, - "mspv": 2, - "request": { - "payload": [ - { - "name": "pgn", - "ctype": "uint16_t", - "desc": "(Optional) PGN ID to query. If omitted, returns all used PGNs", - "units": "", - "optional": true - } - ] - }, - "reply": { - "payload": [ - { - "name": "pgn", - "ctype": "uint16_t", - "desc": "Parameter Group Number (PGN) ID", - "units": "" - }, - { - "name": "startIndex", - "ctype": "uint16_t", - "desc": "Absolute index of the first setting in this group", - "units": "" - }, - { - "name": "endIndex", - "ctype": "uint16_t", - "desc": "Absolute index of the last setting in this group", - "units": "" - } - ], - "repeating": "for each PGN found" - }, - "variable_len": "for each PGN found", - "notes": "Allows efficient fetching of related settings by group.", - "description": "Gets a list of Parameter Group Numbers (PGNs) used by settings, along with the start and end setting indexes for each group. Can request info for a single PGN." - }, - "MSP2_COMMON_SERIAL_CONFIG": { - "code": 4105, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "identifier", - "ctype": "uint8_t", - "desc": "Port identifier Enum (`serialPortIdentifier_e`)", - "units": "", - "enum": "serialPortIdentifier_e" - }, - { - "name": "functionMask", - "ctype": "uint32_t", - "desc": "Bitmask: enabled functions (`FUNCTION_*`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "mspBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for MSP function", - "units": "" - }, - { - "name": "gpsBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for GPS function", - "units": "" - }, - { - "name": "telemetryBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for Telemetry function", - "units": "" - }, - { - "name": "peripheralBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for other peripheral functions", - "units": "" - } - ], - "repeating": "for each available serial port" - }, - "variable_len": "for each available serial port", - "notes": "Baud rate indexes map to actual baud rates (e.g., 9600, 115200). See `baudRates` array.", - "description": "Retrieves the configuration for all available serial ports." - }, - "MSP2_COMMON_SET_SERIAL_CONFIG": { - "code": 4106, - "mspv": 2, - "request": { - "payload": [ - { - "name": "identifier", - "ctype": "uint8_t", - "desc": "Port identifier Enum (`serialPortIdentifier_e`)", - "units": "", - "enum": "serialPortIdentifier_e" - }, - { - "name": "functionMask", - "ctype": "uint32_t", - "desc": "Bitmask: functions to enable", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "mspBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for MSP", - "units": "" - }, - { - "name": "gpsBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for GPS", - "units": "" - }, - { - "name": "telemetryBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for Telemetry", - "units": "" - }, - { - "name": "peripheralBaudIndex", - "ctype": "uint8_t", - "desc": "Baud rate index for peripherals", - "units": "" - } - ], - "repeating": "for each port being configured" - }, - "reply": null, - "variable_len": "for each port being configured", - "notes": "Payload size must be a multiple of the size of one port config entry (1 + 4 + 4 = 9 bytes). Returns error if identifier is invalid or size is incorrect. Baud rate indexes are constrained `BAUD_MIN` to `BAUD_MAX`.", - "description": "Sets the configuration for one or more serial ports." - }, - "MSP2_COMMON_SET_RADAR_POS": { - "code": 4107, - "mspv": 2, - "request": { - "payload": [ - { - "name": "poiIndex", - "ctype": "uint8_t", - "desc": "Index of the POI slot (0 to `RADAR_MAX_POIS - 1`)", - "units": "Index" - }, - { - "name": "state", - "ctype": "uint8_t", - "desc": "Status of the POI (0=undefined, 1=armed, 2=lost)", - "units": "" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude of the POI", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude of the POI", - "units": "deg * 1e7" - }, - { - "name": "altitude", - "ctype": "int32_t", - "desc": "Altitude of the POI", - "units": "cm" - }, - { - "name": "heading", - "ctype": "uint16_t", - "desc": "Heading of the POI", - "units": "degrees" - }, - { - "name": "speed", - "ctype": "uint16_t", - "desc": "Speed of the POI", - "units": "cm/s" - }, - { - "name": "linkQuality", - "ctype": "uint8_t", - "desc": "Link quality indicator", - "units": "0-4" - } - ] - }, - "reply": null, - "notes": "Expects 19 bytes. POI index is clamped to `RADAR_MAX_POIS - 1`. Updates the `radar_pois` array.", - "description": "Sets the position and status information for a \"radar\" Point of Interest (POI). Used for displaying other craft/objects on the OSD map." - }, - "MSP2_COMMON_SET_RADAR_ITD": { - "code": 4108, - "mspv": 2, - "request": null, - "reply": null, - "not_implemented": true, - "notes": "Not implemented in INAV `fc_msp.c`.", - "description": "Sets radar information to display (likely internal/unused)." - }, - "MSP2_COMMON_SET_MSP_RC_LINK_STATS": { - "code": 4109, - "mspv": 2, - "request": { - "payload": [ - { - "name": "sublinkID", - "ctype": "uint8_t", - "desc": "Sublink identifier (usually 0)" - }, - { - "name": "validLink", - "ctype": "uint8_t", - "desc": "Indicates if the link is currently valid (not in failsafe)", - "units": "Boolean" - }, - { - "name": "rssiPercent", - "ctype": "uint8_t", - "desc": "Uplink RSSI percentage (0-100)", - "units": "%" - }, - { - "name": "uplinkRSSI_dBm", - "ctype": "uint8_t", - "desc": "Uplink RSSI in dBm (sent as positive, e.g., 70 means -70dBm)", - "units": "-dBm" - }, - { - "name": "downlinkLQ", - "ctype": "uint8_t", - "desc": "Downlink Link Quality (0-100)", - "units": "%" - }, - { - "name": "uplinkLQ", - "ctype": "uint8_t", - "desc": "Uplink Link Quality (0-100)", - "units": "%" - }, - { - "name": "uplinkSNR", - "ctype": "int8_t", - "desc": "Uplink Signal-to-Noise Ratio", - "units": "dB" - } - ] - }, - "reply": null, - "notes": "Requires `USE_RX_MSP`. Expects at least 7 bytes. Updates `rxLinkStatistics` and sets RSSI via `setRSSIFromMSP_RC()` only if `sublinkID` is 0. This message expects **no reply** (`MSP_RESULT_NO_REPLY`).", - "description": "Provides RC link statistics (RSSI, LQ) to the FC, typically from an MSP-based RC link (like ExpressLRS). Sent periodically by the RC link." - }, - "MSP2_COMMON_SET_MSP_RC_INFO": { - "code": 4110, - "mspv": 2, - "request": { - "payload": [ - { - "name": "sublinkID", - "ctype": "uint8_t", - "desc": "Sublink identifier (usually 0)" - }, - { - "name": "uplinkTxPower", - "ctype": "uint16_t", - "desc": "Uplink transmitter power level", - "units": "mW" - }, - { - "name": "downlinkTxPower", - "ctype": "uint16_t", - "desc": "Downlink transmitter power level", - "units": "mW" - }, - { - "name": "band", - "ctype": "char", - "desc": "Operating band string (e.g., \"2G4\", \"900\"), null-terminated/padded", - "array": true, - "array_size": 4 - }, - { - "name": "mode", - "ctype": "char", - "desc": "Operating mode/rate string (e.g., \"100HZ\", \"F1000\"), null-terminated/padded", - "array": true, - "array_size": 6 - } - ] - }, - "reply": null, - "notes": "Requires `USE_RX_MSP`. Expects at least 15 bytes. Updates `rxLinkStatistics` only if `sublinkID` is 0. Converts band/mode strings to uppercase. This message expects **no reply** (`MSP_RESULT_NO_REPLY`).", - "description": "Provides additional RC link information (power levels, band, mode) to the FC from an MSP-based RC link. Sent less frequently than link stats." - }, - "MSP2_COMMON_GET_RADAR_GPS": { - "code": 4111, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "poiLatitude", - "ctype": "int32_t", - "desc": "Latitude of a radar POI", - "units": "deg * 1e7" - }, - { - "name": "poiLongitude", - "ctype": "int32_t", - "desc": "Longitude of a radar POI", - "units": "deg * 1e7" - }, - { - "name": "poiAltitude", - "ctype": "int32_t", - "desc": "Altitude of a radar POI", - "units": "cm" - } - ], - "repeating": "RADAR_MAX_POIS" - }, - "notes": "Returns the stored GPS coordinates for all radar POIs (`radar_pois[i].gps`).", - "description": "Provides the GPS positions (latitude, longitude, altitude) for each radar point of interest." - }, - "MSP2_SENSOR_RANGEFINDER": { - "code": 7937, - "mspv": 2, - "request": { - "payload": [ - { - "name": "quality", - "ctype": "uint8_t", - "desc": "Quality of the measurement", - "units": "0-255" - }, - { - "name": "distanceMm", - "ctype": "int32_t", - "desc": "Measured distance. Negative value indicates out of range", - "units": "mm" - } - ] - }, - "reply": null, - "notes": "Requires `USE_RANGEFINDER_MSP`. Calls `mspRangefinderReceiveNewData()`.", - "description": "Provides rangefinder data (distance, quality) from an external MSP-based sensor." - }, - "MSP2_SENSOR_OPTIC_FLOW": { - "code": 7938, - "mspv": 2, - "request": { - "payload": [ - { - "name": "quality", - "ctype": "uint8_t", - "desc": "Quality of the measurement (0-255)", - "units": "" - }, - { - "name": "motionX", - "ctype": "int32_t", - "desc": "Raw integrated flow value X", - "units": "" - }, - { - "name": "motionY", - "ctype": "int32_t", - "desc": "Raw integrated flow value Y", - "units": "" - } - ] - }, - "reply": null, - "notes": "Requires `USE_OPFLOW_MSP`. Calls `mspOpflowReceiveNewData()`.", - "description": "Provides optical flow data (motion, quality) from an external MSP-based sensor." - }, - "MSP2_SENSOR_GPS": { - "code": 7939, - "mspv": 2, - "request": { - "payload": [ - { - "name": "instance", - "ctype": "uint8_t", - "desc": "Sensor instance number (for multi-GPS)" - }, - { - "name": "gpsWeek", - "ctype": "uint16_t", - "desc": "GPS week number (0xFFFF if unavailable)" - }, - { - "name": "msTOW", - "ctype": "uint32_t", - "desc": "Milliseconds Time of Week", - "units": "ms" - }, - { - "name": "fixType", - "ctype": "uint8_t", - "desc": "Enum `gpsFixType_e` Type of GPS fix", - "units": "Enum", - "enum": "gpsFixType_e" - }, - { - "name": "satellitesInView", - "ctype": "uint8_t", - "desc": "Number of satellites used in solution", - "units": "Count" - }, - { - "name": "hPosAccuracy", - "ctype": "uint16_t", - "desc": "Horizontal position accuracy estimate in milimeters", - "units": "mm" - }, - { - "name": "vPosAccuracy", - "ctype": "uint16_t", - "desc": "Vertical position accuracy estimate in milimeters", - "units": "mm" - }, - { - "name": "hVelAccuracy", - "ctype": "uint16_t", - "desc": "Horizontal velocity accuracy estimate", - "units": "cm/s" - }, - { - "name": "hdop", - "ctype": "uint16_t", - "desc": "Horizontal Dilution of Precision", - "units": "HDOP * 100" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude", - "units": "deg * 1e7" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude", - "units": "deg * 1e7" - }, - { - "name": "mslAltitude", - "ctype": "int32_t", - "desc": "Altitude above Mean Sea Level", - "units": "cm" - }, - { - "name": "nedVelNorth", - "ctype": "int32_t", - "desc": "North velocity (NED frame)", - "units": "cm/s" - }, - { - "name": "nedVelEast", - "ctype": "int32_t", - "desc": "East velocity (NED frame)", - "units": "cm/s" - }, - { - "name": "nedVelDown", - "ctype": "int32_t", - "desc": "Down velocity (NED frame)", - "units": "cm/s" - }, - { - "name": "groundCourse", - "ctype": "uint16_t", - "desc": "Ground course (0-36000)", - "units": "deg * 100" - }, - { - "name": "trueYaw", - "ctype": "uint16_t", - "desc": "True heading/yaw (0-36000, 65535 if unavailable)", - "units": "deg * 100" - }, - { - "name": "year", - "ctype": "uint16_t", - "desc": "Year (e.g., 2023)" - }, - { - "name": "month", - "ctype": "uint8_t", - "desc": "Month (1-12)" - }, - { - "name": "day", - "ctype": "uint8_t", - "desc": "Day of month (1-31)" - }, - { - "name": "hour", - "ctype": "uint8_t", - "desc": "Hour (0-23)" - }, - { - "name": "min", - "ctype": "uint8_t", - "desc": "Minute (0-59)" - }, - { - "name": "sec", - "ctype": "uint8_t", - "desc": "Second (0-59)" - } - ] - }, - "reply": null, - "notes": "Requires `USE_GPS_PROTO_MSP`. Calls `mspGPSReceiveNewData()`.", - "description": "Provides detailed GPS data from an external MSP-based GPS module." - }, - "MSP2_SENSOR_COMPASS": { - "code": 7940, - "mspv": 2, - "request": { - "payload": [ - { - "name": "instance", - "ctype": "uint8_t", - "desc": "Sensor instance number" - }, - { - "name": "timeMs", - "ctype": "uint32_t", - "desc": "Timestamp from the sensor", - "units": "ms" - }, - { - "name": "magX", - "ctype": "int16_t", - "desc": "Front component reading", - "units": "mGauss" - }, - { - "name": "magY", - "ctype": "int16_t", - "desc": "Right component reading", - "units": "mGauss" - }, - { - "name": "magZ", - "ctype": "int16_t", - "desc": "Down component reading", - "units": "mGauss" - } - ] - }, - "reply": null, - "notes": "Requires `USE_MAG_MSP`. Calls `mspMagReceiveNewData()`.", - "description": "Provides magnetometer data from an external MSP-based compass module." - }, - "MSP2_SENSOR_BAROMETER": { - "code": 7941, - "mspv": 2, - "request": { - "payload": [ - { - "name": "instance", - "ctype": "uint8_t", - "desc": "Sensor instance number" - }, - { - "name": "timeMs", - "ctype": "uint32_t", - "desc": "Timestamp from the sensor", - "units": "ms" - }, - { - "name": "pressurePa", - "ctype": "float", - "desc": "Absolute pressure", - "units": "Pa" - }, - { - "name": "temp", - "ctype": "int16_t", - "desc": "Temperature", - "units": "0.01 deg C" - } - ] - }, - "reply": null, - "notes": "Requires `USE_BARO_MSP`. Calls `mspBaroReceiveNewData()`.", - "description": "Provides barometer data from an external MSP-based barometer module." - }, - "MSP2_SENSOR_AIRSPEED": { - "code": 7942, - "mspv": 2, - "request": { - "payload": [ - { - "name": "instance", - "ctype": "uint8_t", - "desc": "Sensor instance number" - }, - { - "name": "timeMs", - "ctype": "uint32_t", - "desc": "Timestamp from the sensor", - "units": "ms" - }, - { - "name": "diffPressurePa", - "ctype": "float", - "desc": "Differential pressure", - "units": "Pa" - }, - { - "name": "temp", - "ctype": "int16_t", - "desc": "Temperature", - "units": "0.01 deg C" - } - ] - }, - "reply": null, - "notes": "Requires `USE_PITOT_MSP`. Calls `mspPitotmeterReceiveNewData()`.", - "description": "Provides airspeed data from an external MSP-based pitot sensor module." - }, - "MSP2_SENSOR_HEADTRACKER": { - "code": 7943, - "mspv": 2, - "request": { - "payload": [ - { - "name": "...", - "ctype": "Varies", - "desc": "", - "polymorph": true, - "units": "Head tracker angles (e.g., int16 Roll, Pitch, Yaw in deci-degrees)" - } - ] - }, - "reply": null, - "variable_len": true, - "notes": "Requires `USE_HEADTRACKER` and `USE_HEADTRACKER_MSP`. Calls `mspHeadTrackerReceiverNewData()`. Payload structure needs verification from `mspHeadTrackerReceiverNewData` implementation.", - "description": "Provides head tracker orientation data." - }, - "MSP2_INAV_STATUS": { - "code": 8192, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "cycleTime", - "ctype": "uint16_t", - "desc": "Main loop cycle time", - "units": "Β΅s" - }, - { - "name": "i2cErrors", - "ctype": "uint16_t", - "desc": "I2C errors", - "units": "Count" - }, - { - "name": "sensorStatus", - "ctype": "uint16_t", - "desc": "Bitmask: Sensor status", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "cpuLoad", - "ctype": "uint16_t", - "desc": "Average system load percentage", - "units": "%" - }, - { - "name": "profileAndBattProfile", - "ctype": "uint8_t", - "desc": "Bits 0-3: Config profile index (`getConfigProfile()`), Bits 4-7: Battery profile index (`getConfigBatteryProfile()`)", - "units": "Packed" - }, - { - "name": "armingFlags", - "ctype": "uint32_t", - "desc": "Bitmask: Full 32-bit flight controller arming flags (`armingFlags`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "activeModes", - "ctype": "boxBitmask_t", - "desc": "Bitmask words for active flight modes (`packBoxModeFlags()`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "mixerProfile", - "ctype": "uint8_t", - "desc": "Current mixer profile index (`getConfigMixerProfile()`)", - "units": "Index" - } - ] - }, - "notes": "`sensorStatus` bits follow `packSensorStatus()` (bit 15 indicates hardware failure). `profileAndBattProfile` packs the current config profile in the low nibble and the battery profile in the high nibble. `activeModes` is emitted as a little-endian array of 32-bit words sized to `CHECKBOX_ITEM_COUNT`.", - "description": "Provides comprehensive flight controller status, extending `MSP_STATUS_EX` with full arming flags, battery profile, and mixer profile." - }, - "MSP2_INAV_OPTICAL_FLOW": { - "code": 8193, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "quality", - "ctype": "uint8_t", - "desc": "Raw quality indicator from the sensor (`opflow.rawQuality`). 0 if `USE_OPFLOW` disabled", - "units": "0-255" - }, - { - "name": "flowRateX", - "ctype": "int16_t", - "desc": "Optical flow rate X (roll axis) (`RADIANS_TO_DEGREES(opflow.flowRate[X])`). 0 if `USE_OPFLOW` disabled", - "units": "degrees/s" - }, - { - "name": "flowRateY", - "ctype": "int16_t", - "desc": "Optical flow rate Y (pitch axis) (`RADIANS_TO_DEGREES(opflow.flowRate[Y])`). 0 if `USE_OPFLOW` disabled", - "units": "degrees/s" - }, - { - "name": "bodyRateX", - "ctype": "int16_t", - "desc": "Compensated body rate X (roll axis) (`RADIANS_TO_DEGREES(opflow.bodyRate[X])`). 0 if `USE_OPFLOW` disabled", - "units": "degrees/s" - }, - { - "name": "bodyRateY", - "ctype": "int16_t", - "desc": "Compensated body rate Y (pitch axis) (`RADIANS_TO_DEGREES(opflow.bodyRate[Y])`). 0 if `USE_OPFLOW` disabled", - "units": "degrees/s" - } - ] - }, - "notes": "Requires `USE_OPFLOW`.", - "description": "Provides data from the optical flow sensor." - }, - "MSP2_INAV_ANALOG": { - "code": 8194, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "batteryFlags", - "ctype": "uint8_t", - "desc": "Bitmask: Bit0=Full on plug-in, Bit1=Use capacity thresholds, Bits2-3=`batteryState_e` (`getBatteryState()`), Bits4-7=Cell count (`getBatteryCellCount()`)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "vbat", - "ctype": "uint16_t", - "desc": "Battery voltage (`getBatteryVoltage()`)", - "units": "0.01V" - }, - { - "name": "amperage", - "ctype": "int16_t", - "desc": "Current draw (`getAmperage()`)", - "units": "0.01A" - }, - { - "name": "powerDraw", - "ctype": "uint32_t", - "desc": "Power draw (`getPower()`)", - "units": "0.01W" - }, - { - "name": "mAhDrawn", - "ctype": "uint32_t", - "desc": "Consumed capacity (`getMAhDrawn()`)", - "units": "mAh" - }, - { - "name": "mWhDrawn", - "ctype": "uint32_t", - "desc": "Consumed energy (`getMWhDrawn()`)", - "units": "mWh" - }, - { - "name": "remainingCapacity", - "ctype": "uint32_t", - "desc": "Estimated remaining capacity (`getBatteryRemainingCapacity()`)", - "units": "Capacity unit (`batteryMetersConfig()->capacity_unit`)" - }, - { - "name": "percentageRemaining", - "ctype": "uint8_t", - "desc": "Estimated remaining capacity percentage (`calculateBatteryPercentage()`)", - "units": "%" - }, - { - "name": "rssi", - "ctype": "uint16_t", - "desc": "RSSI value (`getRSSI()`)", - "units": "Raw (0-1023)" - } - ] - }, - "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_MISC": { - "code": 8195, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "midRc", - "ctype": "uint16_t", - "desc": "Mid RC value (`PWM_RANGE_MIDDLE`)", - "units": "PWM" - }, - { - "name": "legacyMinThrottle", - "ctype": "uint16_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "maxThrottle", - "ctype": "uint16_t", - "desc": "Maximum throttle command (`getMaxThrottle()`)", - "units": "PWM" - }, - { - "name": "minCommand", - "ctype": "uint16_t", - "desc": "Minimum motor command (`motorConfig()->mincommand`)", - "units": "PWM" - }, - { - "name": "failsafeThrottle", - "ctype": "uint16_t", - "desc": "Failsafe throttle level (`currentBatteryProfile->failsafe_throttle`)", - "units": "PWM" - }, - { - "name": "gpsType", - "ctype": "uint8_t", - "desc": "Enum `gpsProvider_e` GPS provider type (`gpsConfig()->provider`). 0 if `USE_GPS` disabled", - "units": "Enum", - "enum": "gpsProvider_e" - }, - { - "name": "legacyGpsBaud", - "ctype": "uint8_t", - "desc": "Always 0 (Legacy)", - "value": 0 - }, - { - "name": "gpsSbasMode", - "ctype": "uint8_t", - "desc": "Enum `sbasMode_e` GPS SBAS mode (`gpsConfig()->sbasMode`). 0 if `USE_GPS` disabled", - "units": "Enum", - "enum": "sbasMode_e" - }, - { - "name": "rssiChannel", - "ctype": "uint8_t", - "desc": "RSSI channel index (1-based, 0 disables) (`rxConfig()->rssi_channel`)", - "units": "Index" - }, - { - "name": "magDeclination", - "ctype": "int16_t", - "desc": "Magnetic declination / 10 (`compassConfig()->mag_declination / 10`). 0 if `USE_MAG` disabled", - "units": "0.1 degrees" - }, - { - "name": "vbatScale", - "ctype": "uint16_t", - "desc": "Voltage scale (`batteryMetersConfig()->voltage.scale`). 0 if `USE_ADC` disabled", - "units": "Scale" - }, - { - "name": "vbatSource", - "ctype": "uint8_t", - "desc": "Enum `batVoltageSource_e` Voltage source (`batteryMetersConfig()->voltageSource`). 0 if `USE_ADC` disabled", - "units": "Enum", - "enum": "batVoltageSource_e" - }, - { - "name": "cellCount", - "ctype": "uint8_t", - "desc": "Configured cell count (`currentBatteryProfile->cells`). 0 if `USE_ADC` disabled", - "units": "Count" - }, - { - "name": "vbatCellDetect", - "ctype": "uint16_t", - "desc": "Cell detection voltage (`currentBatteryProfile->voltage.cellDetect`). 0 if `USE_ADC` disabled", - "units": "0.01V" - }, - { - "name": "vbatMinCell", - "ctype": "uint16_t", - "desc": "Min cell voltage (`currentBatteryProfile->voltage.cellMin`). 0 if `USE_ADC` disabled", - "units": "0.01V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint16_t", - "desc": "Max cell voltage (`currentBatteryProfile->voltage.cellMax`). 0 if `USE_ADC` disabled", - "units": "0.01V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint16_t", - "desc": "Warning cell voltage (`currentBatteryProfile->voltage.cellWarning`). 0 if `USE_ADC` disabled", - "units": "0.01V" - }, - { - "name": "capacityValue", - "ctype": "uint32_t", - "desc": "Battery capacity (`currentBatteryProfile->capacity.value`)", - "units": "mAh/mWh" - }, - { - "name": "capacityWarning", - "ctype": "uint32_t", - "desc": "Capacity warning threshold (`currentBatteryProfile->capacity.warning`)", - "units": "mAh/mWh" - }, - { - "name": "capacityCritical", - "ctype": "uint32_t", - "desc": "Capacity critical threshold (`currentBatteryProfile->capacity.critical`)", - "units": "mAh/mWh" - }, - { - "name": "capacityUnit", - "ctype": "uint8_t", - "desc": "Enum `batCapacityUnit_e` Capacity unit (`batteryMetersConfig()->capacity_unit`)", - "units": "Enum", - "enum": "batCapacityUnit_e" - } - ] - }, - "notes": "", - "description": "Retrieves miscellaneous configuration settings, superseding `MSP_MISC` with higher precision and capacity fields." - }, - "MSP2_INAV_SET_MISC": { - "code": 8196, - "mspv": 2, - "request": { - "payload": [ - { - "name": "midRc", - "ctype": "uint16_t", - "desc": "Ignored", - "units": "PWM" - }, - { - "name": "legacyMinThrottle", - "ctype": "uint16_t", - "desc": "Ignored" - }, - { - "name": "legacyMaxThrottle", - "ctype": "uint16_t", - "desc": "Ignored" - }, - { - "name": "minCommand", - "ctype": "uint16_t", - "desc": "Sets `motorConfigMutable()->mincommand` (constrained)", - "units": "PWM" - }, - { - "name": "failsafeThrottle", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->failsafe_throttle` (constrained)", - "units": "PWM" - }, - { - "name": "gpsType", - "ctype": "uint8_t", - "desc": "Enum `gpsProvider_e` Sets `gpsConfigMutable()->provider` (if `USE_GPS`)", - "units": "Enum", - "enum": "gpsProvider_e" - }, - { - "name": "legacyGpsBaud", - "ctype": "uint8_t", - "desc": "Ignored" - }, - { - "name": "gpsSbasMode", - "ctype": "uint8_t", - "desc": "Enum `sbasMode_e` Sets `gpsConfigMutable()->sbasMode` (if `USE_GPS`)", - "units": "Enum", - "enum": "sbasMode_e" - }, - { - "name": "rssiChannel", - "ctype": "uint8_t", - "desc": "Sets `rxConfigMutable()->rssi_channel` (1-based, 0 disables) when <= `MAX_SUPPORTED_RC_CHANNEL_COUNT`", - "units": "Index" - }, - { - "name": "magDeclination", - "ctype": "int16_t", - "desc": "Sets `compassConfigMutable()->mag_declination = value * 10` (if `USE_MAG`)", - "units": "0.1 degrees" - }, - { - "name": "vbatScale", - "ctype": "uint16_t", - "desc": "Sets `batteryMetersConfigMutable()->voltage.scale` (if `USE_ADC`)", - "units": "Scale" - }, - { - "name": "vbatSource", - "ctype": "uint8_t", - "desc": "Enum `batVoltageSource_e` Sets `batteryMetersConfigMutable()->voltageSource` (if `USE_ADC`, validated)", - "units": "Enum", - "enum": "batVoltageSource_e" - }, - { - "name": "cellCount", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->cells` (if `USE_ADC`)", - "units": "Count" - }, - { - "name": "vbatCellDetect", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellDetect` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "vbatMinCell", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "capacityValue", - "ctype": "uint32_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.value`", - "units": "mAh/mWh" - }, - { - "name": "capacityWarning", - "ctype": "uint32_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.warning`", - "units": "mAh/mWh" - }, - { - "name": "capacityCritical", - "ctype": "uint32_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.critical`", - "units": "mAh/mWh" - }, - { - "name": "capacityUnit", - "ctype": "uint8_t", - "desc": "Enum `batCapacityUnit_e` Sets `batteryMetersConfigMutable()->capacity_unit` (validated, updates OSD energy unit if changed)", - "units": "Enum", - "enum": "batCapacityUnit_e" - } - ] - }, - "reply": null, - "notes": "Expects 41 bytes. Performs validation on `vbatSource` and `capacityUnit`.", - "description": "Sets miscellaneous configuration settings, superseding `MSP_SET_MISC`." - }, - "MSP2_INAV_BATTERY_CONFIG": { - "code": 8197, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "vbatScale", - "ctype": "uint16_t", - "desc": "Voltage scale (`batteryMetersConfig()->voltage.scale`)", - "units": "Scale" - }, - { - "name": "vbatSource", - "ctype": "uint8_t", - "desc": "Enum `batVoltageSource_e` Voltage source (`batteryMetersConfig()->voltageSource`)", - "units": "Enum", - "enum": "batVoltageSource_e" - }, - { - "name": "cellCount", - "ctype": "uint8_t", - "desc": "Configured cell count (`currentBatteryProfile->cells`)", - "units": "Count" - }, - { - "name": "vbatCellDetect", - "ctype": "uint16_t", - "desc": "Cell detection voltage (`currentBatteryProfile->voltage.cellDetect`)", - "units": "0.01V" - }, - { - "name": "vbatMinCell", - "ctype": "uint16_t", - "desc": "Min cell voltage (`currentBatteryProfile->voltage.cellMin`)", - "units": "0.01V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint16_t", - "desc": "Max cell voltage (`currentBatteryProfile->voltage.cellMax`)", - "units": "0.01V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint16_t", - "desc": "Warning cell voltage (`currentBatteryProfile->voltage.cellWarning`)", - "units": "0.01V" - }, - { - "name": "currentOffset", - "ctype": "int16_t", - "desc": "Current sensor offset (`batteryMetersConfig()->current.offset`)", - "units": "mV" - }, - { - "name": "currentScale", - "ctype": "int16_t", - "desc": "Current sensor scale (`batteryMetersConfig()->current.scale`)", - "units": "0.1 mV/A" - }, - { - "name": "capacityValue", - "ctype": "uint32_t", - "desc": "Battery capacity (`currentBatteryProfile->capacity.value`)", - "units": "mAh/mWh" - }, - { - "name": "capacityWarning", - "ctype": "uint32_t", - "desc": "Capacity warning threshold (`currentBatteryProfile->capacity.warning`)", - "units": "mAh/mWh" - }, - { - "name": "capacityCritical", - "ctype": "uint32_t", - "desc": "Capacity critical threshold (`currentBatteryProfile->capacity.critical`)", - "units": "mAh/mWh" - }, - { - "name": "capacityUnit", - "ctype": "uint8_t", - "desc": "Enum `batCapacityUnit_e` Capacity unit (`batteryMetersConfig()->capacity_unit`)", - "units": "Enum", - "enum": "batCapacityUnit_e" - } - ] - }, - "notes": "Fields are 0 if `USE_ADC` is not defined.", - "description": "Retrieves the configuration specific to the battery voltage and current sensors and capacity settings for the current battery profile." - }, - "MSP2_INAV_SET_BATTERY_CONFIG": { - "code": 8198, - "mspv": 2, - "request": { - "payload": [ - { - "name": "vbatScale", - "ctype": "uint16_t", - "desc": "Sets `batteryMetersConfigMutable()->voltage.scale` (if `USE_ADC`)", - "units": "Scale" - }, - { - "name": "vbatSource", - "ctype": "uint8_t", - "desc": "Enum `batVoltageSource_e` Sets `batteryMetersConfigMutable()->voltageSource` (if `USE_ADC`, validated)", - "units": "Enum", - "enum": "batVoltageSource_e" - }, - { - "name": "cellCount", - "ctype": "uint8_t", - "desc": "Sets `currentBatteryProfileMutable->cells` (if `USE_ADC`)", - "units": "Count" - }, - { - "name": "vbatCellDetect", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellDetect` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "vbatMinCell", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "vbatMaxCell", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "vbatWarningCell", - "ctype": "uint16_t", - "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning` (if `USE_ADC`)", - "units": "0.01V" - }, - { - "name": "currentOffset", - "ctype": "int16_t", - "desc": "Sets `batteryMetersConfigMutable()->current.offset`", - "units": "mV" - }, - { - "name": "currentScale", - "ctype": "int16_t", - "desc": "Sets `batteryMetersConfigMutable()->current.scale`", - "units": "0.1 mV/A" - }, - { - "name": "capacityValue", - "ctype": "uint32_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.value`", - "units": "mAh/mWh" - }, - { - "name": "capacityWarning", - "ctype": "uint32_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.warning`", - "units": "mAh/mWh" - }, - { - "name": "capacityCritical", - "ctype": "uint32_t", - "desc": "Sets `currentBatteryProfileMutable->capacity.critical`", - "units": "mAh/mWh" - }, - { - "name": "capacityUnit", - "ctype": "uint8_t", - "desc": "Enum `batCapacityUnit_e` Sets `batteryMetersConfigMutable()->capacity_unit` (validated, updates OSD energy unit if changed)", - "units": "Enum", - "enum": "batCapacityUnit_e" - } - ] - }, - "reply": null, - "notes": "Expects 29 bytes. Performs validation on `vbatSource` and `capacityUnit`.", - "description": "Sets the battery voltage/current sensor configuration and capacity settings for the current battery profile." - }, - "MSP2_INAV_RATE_PROFILE": { - "code": 8199, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "throttleMid", - "ctype": "uint8_t", - "desc": "Throttle Midpoint (`currentControlRateProfile->throttle.rcMid8`)", - "units": "" - }, - { - "name": "throttleExpo", - "ctype": "uint8_t", - "desc": "Throttle Expo (`currentControlRateProfile->throttle.rcExpo8`)", - "units": "" - }, - { - "name": "dynamicThrottlePID", - "ctype": "uint8_t", - "desc": "TPA value (`currentControlRateProfile->throttle.dynPID`)", - "units": "" - }, - { - "name": "tpaBreakpoint", - "ctype": "uint16_t", - "desc": "TPA breakpoint (`currentControlRateProfile->throttle.pa_breakpoint`)", - "units": "" - }, - { - "name": "stabRcExpo", - "ctype": "uint8_t", - "desc": "Stabilized Roll/Pitch Expo (`currentControlRateProfile->stabilized.rcExpo8`)", - "units": "" - }, - { - "name": "stabRcYawExpo", - "ctype": "uint8_t", - "desc": "Stabilized Yaw Expo (`currentControlRateProfile->stabilized.rcYawExpo8`)", - "units": "" - }, - { - "name": "stabRollRate", - "ctype": "uint8_t", - "desc": "Stabilized Roll Rate (`currentControlRateProfile->stabilized.rates[FD_ROLL]`)", - "units": "" - }, - { - "name": "stabPitchRate", - "ctype": "uint8_t", - "desc": "Stabilized Pitch Rate (`currentControlRateProfile->stabilized.rates[FD_PITCH]`)", - "units": "" - }, - { - "name": "stabYawRate", - "ctype": "uint8_t", - "desc": "Stabilized Yaw Rate (`currentControlRateProfile->stabilized.rates[FD_YAW]`)", - "units": "" - }, - { - "name": "manualRcExpo", - "ctype": "uint8_t", - "desc": "Manual Roll/Pitch Expo (`currentControlRateProfile->manual.rcExpo8`)", - "units": "" - }, - { - "name": "manualRcYawExpo", - "ctype": "uint8_t", - "desc": "Manual Yaw Expo (`currentControlRateProfile->manual.rcYawExpo8`)", - "units": "" - }, - { - "name": "manualRollRate", - "ctype": "uint8_t", - "desc": "Manual Roll Rate (`currentControlRateProfile->manual.rates[FD_ROLL]`)", - "units": "" - }, - { - "name": "manualPitchRate", - "ctype": "uint8_t", - "desc": "Manual Pitch Rate (`currentControlRateProfile->manual.rates[FD_PITCH]`)", - "units": "" - }, - { - "name": "manualYawRate", - "ctype": "uint8_t", - "desc": "Manual Yaw Rate (`currentControlRateProfile->manual.rates[FD_YAW]`)", - "units": "" - } - ] - }, - "notes": "", - "description": "Retrieves the rates and expos for the current control rate profile, including both stabilized and manual flight modes. Supersedes `MSP_RC_TUNING`." - }, - "MSP2_INAV_SET_RATE_PROFILE": { - "code": 8200, - "mspv": 2, - "request": { - "payload": [ - { - "name": "throttleMid", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->throttle.rcMid8`", - "units": "" - }, - { - "name": "throttleExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->throttle.rcExpo8`", - "units": "" - }, - { - "name": "dynamicThrottlePID", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->throttle.dynPID`", - "units": "" - }, - { - "name": "tpaBreakpoint", - "ctype": "uint16_t", - "desc": "Sets `currentControlRateProfile->throttle.pa_breakpoint`", - "units": "" - }, - { - "name": "stabRcExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rcExpo8`", - "units": "" - }, - { - "name": "stabRcYawExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rcYawExpo8`", - "units": "" - }, - { - "name": "stabRollRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_ROLL]` (constrained)", - "units": "" - }, - { - "name": "stabPitchRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_PITCH]` (constrained)", - "units": "" - }, - { - "name": "stabYawRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_YAW]` (constrained)", - "units": "" - }, - { - "name": "manualRcExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->manual.rcExpo8`", - "units": "" - }, - { - "name": "manualRcYawExpo", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->manual.rcYawExpo8`", - "units": "" - }, - { - "name": "manualRollRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->manual.rates[FD_ROLL]` (constrained)", - "units": "" - }, - { - "name": "manualPitchRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->manual.rates[FD_PITCH]` (constrained)", - "units": "" - }, - { - "name": "manualYawRate", - "ctype": "uint8_t", - "desc": "Sets `currentControlRateProfile->manual.rates[FD_YAW]` (constrained)", - "units": "" - } - ] - }, - "reply": null, - "notes": "Expects 15 bytes. Constraints applied to rates based on axis.", - "description": "Sets the rates and expos for the current control rate profile (stabilized and manual). Supersedes `MSP_SET_RC_TUNING`." - }, - "MSP2_INAV_AIR_SPEED": { - "code": 8201, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "airspeed", - "ctype": "uint32_t", - "desc": "Estimated/measured airspeed (`getAirspeedEstimate()`, cm/s). 0 if unavailable", - "units": "cm/s" - } - ] - }, - "notes": "Requires `USE_PITOT`; returns 0 when pitot functionality is not enabled or calibrated.", - "description": "Retrieves the estimated or measured airspeed." - }, - "MSP2_INAV_OUTPUT_MAPPING": { - "code": 8202, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "usageFlags", - "ctype": "uint8_t", - "desc": "Timer usage flags (lower 8 bits of `timerHardware[i].usageFlags`, e.g. `TIM_USE_MOTOR`, `TIM_USE_SERVO`)", - "units": "" - } - ], - "repeating": "for each Motor/Servo timer" - }, - "variable_len": "for each Motor/Servo timer", - "notes": "Superseded by `MSP2_INAV_OUTPUT_MAPPING_EXT2`. Only includes timers *not* used for PPM/PWM input.", - "description": "Retrieves the output mapping configuration (identifies which timer outputs are used for Motors/Servos). Legacy version sending only 8-bit usage flags." - }, - "MSP2_INAV_MC_BRAKING": { - "code": 8203, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "brakingSpeedThreshold", - "ctype": "uint16_t", - "desc": "Speed above which braking engages (`navConfig()->mc.braking_speed_threshold`)", - "units": "cm/s" - }, - { - "name": "brakingDisengageSpeed", - "ctype": "uint16_t", - "desc": "Speed below which braking disengages (`navConfig()->mc.braking_disengage_speed`)", - "units": "cm/s" - }, - { - "name": "brakingTimeout", - "ctype": "uint16_t", - "desc": "Timeout before braking force reduces (`navConfig()->mc.braking_timeout`)", - "units": "ms" - }, - { - "name": "brakingBoostFactor", - "ctype": "uint8_t", - "desc": "Boost factor applied during braking (`navConfig()->mc.braking_boost_factor`)", - "units": "%" - }, - { - "name": "brakingBoostTimeout", - "ctype": "uint16_t", - "desc": "Timeout for the boost factor (`navConfig()->mc.braking_boost_timeout`)", - "units": "ms" - }, - { - "name": "brakingBoostSpeedThreshold", - "ctype": "uint16_t", - "desc": "Speed threshold for boost engagement (`navConfig()->mc.braking_boost_speed_threshold`)", - "units": "cm/s" - }, - { - "name": "brakingBoostDisengageSpeed", - "ctype": "uint16_t", - "desc": "Speed threshold for boost disengagement (`navConfig()->mc.braking_boost_disengage_speed`)", - "units": "cm/s" - }, - { - "name": "brakingBankAngle", - "ctype": "uint8_t", - "desc": "Maximum bank angle allowed during braking (`navConfig()->mc.braking_bank_angle`)", - "units": "degrees" - } - ] - }, - "notes": "Payload is empty if `USE_MR_BRAKING_MODE` is not defined.", - "description": "Retrieves configuration parameters for the multirotor braking mode feature." - }, - "MSP2_INAV_SET_MC_BRAKING": { - "code": 8204, - "mspv": 2, - "request": { - "payload": [ - { - "name": "brakingSpeedThreshold", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->mc.braking_speed_threshold`", - "units": "cm/s" - }, - { - "name": "brakingDisengageSpeed", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->mc.braking_disengage_speed`", - "units": "cm/s" - }, - { - "name": "brakingTimeout", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->mc.braking_timeout`", - "units": "ms" - }, - { - "name": "brakingBoostFactor", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->mc.braking_boost_factor`", - "units": "%" - }, - { - "name": "brakingBoostTimeout", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->mc.braking_boost_timeout`", - "units": "ms" - }, - { - "name": "brakingBoostSpeedThreshold", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->mc.braking_boost_speed_threshold`", - "units": "cm/s" - }, - { - "name": "brakingBoostDisengageSpeed", - "ctype": "uint16_t", - "desc": "Sets `navConfigMutable()->mc.braking_boost_disengage_speed`", - "units": "cm/s" - }, - { - "name": "brakingBankAngle", - "ctype": "uint8_t", - "desc": "Sets `navConfigMutable()->mc.braking_bank_angle`", - "units": "degrees" - } - ] - }, - "reply": null, - "notes": "Expects 14 bytes. Returns error if `USE_MR_BRAKING_MODE` is not defined.", - "description": "Sets configuration parameters for the multirotor braking mode feature." - }, - "MSP2_INAV_OUTPUT_MAPPING_EXT": { - "code": 8205, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "timerId", - "ctype": "uint8_t", - "desc": "Hardware timer identifier (e.g., `TIM1`, `TIM2`). Value depends on target", - "units": "" - }, - { - "name": "usageFlags", - "ctype": "uint8_t", - "desc": "Timer usage flags (lower 8 bits of `timerHardware[i].usageFlags`, e.g. `TIM_USE_MOTOR`, `TIM_USE_SERVO`)", - "units": "" - } - ], - "repeating": "for each Motor/Servo timer" - }, - "variable_len": "for each Motor/Servo timer", - "notes": "Usage flags are truncated to 8 bits. `timerId` mapping is target-specific.", - "description": "Retrieves extended output mapping configuration (timer ID and usage flags). Obsolete, use `MSP2_INAV_OUTPUT_MAPPING_EXT2`." - }, - "MSP2_INAV_TIMER_OUTPUT_MODE": { - "code": 8206, - "mspv": 2, - "request": null, - "reply": null, - "variable_len": true, - "notes": "Non-SITL only. HARDWARE_TIMER_DEFINITION_COUNT is target specific. Returns MSP_RESULT_ACK on success, MSP_RESULT_ERROR on invalid timer index.", - "description": "Reads timer output mode overrides.", - "variants": { - "dataSize == 0": { - "description": "List all timers", - "request": null, - "reply": { - "payload": [ - { - "name": "timerIndex", - "ctype": "uint8_t", - "desc": "Timer index" - }, - { - "name": "outputMode", - "ctype": "uint8_t", - "enum": "outputMode_e", - "desc": "OUTPUT_MODE_*" - } - ], - "repeating": "HARDWARE_TIMER_DEFINITION_COUNT" - } + "MSP_WP": { + "code": 118, + "mspv": 1, + "request": { + "payload": [ + { + "name": "waypointIndex", + "ctype": "uint8_t", + "desc": "Index of the waypoint to retrieve (0 to `NAV_MAX_WAYPOINTS - 1`)", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "waypointIndex", + "ctype": "uint8_t", + "desc": "Index of the returned waypoint", + "units": "Index" + }, + { + "name": "action", + "ctype": "uint8_t", + "desc": "Enum `navWaypointActions_e` Waypoint action type", + "units": "Enum", + "enum": "navWaypointActions_e" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude coordinate", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude coordinate", + "units": "deg * 1e7" + }, + { + "name": "altitude", + "ctype": "int32_t", + "desc": "Altitude coordinate (relative to home or sea level, see flag)", + "units": "cm" + }, + { + "name": "param1", + "ctype": "int16_t", + "desc": "Parameter 1 (meaning depends on action)", + "units": "Varies" + }, + { + "name": "param2", + "ctype": "int16_t", + "desc": "Parameter 2 (meaning depends on action)", + "units": "Varies" + }, + { + "name": "param3", + "ctype": "int16_t", + "desc": "Parameter 3 (meaning depends on action)", + "units": "Varies" + }, + { + "name": "flag", + "ctype": "uint8_t", + "desc": "Bitmask: Waypoint flags (`NAV_WP_FLAG_*`)", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "notes": "See `navWaypoint_t` and `navWaypointActions_e`.", + "description": "Get/Set a single waypoint from the mission plan." + }, + "MSP_BOXIDS": { + "code": 119, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "boxIds", + "desc": "Array of permanent IDs for each configured box (`serializeBoxReply()`). Length depends on number of boxes", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Useful for mapping mode range configurations (`MSP_MODE_RANGES`) back to user-understandable modes via `MSP_BOXNAMES`.", + "description": "Provides a list of permanent IDs associated with the available flight modes (boxes)." + }, + "MSP_SERVO_CONFIGURATIONS": { + "code": 120, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "min", + "ctype": "int16_t", + "desc": "Minimum servo endpoint (`servoParams(i)->min`)", + "units": "PWM" + }, + { + "name": "max", + "ctype": "int16_t", + "desc": "Maximum servo endpoint (`servoParams(i)->max`)", + "units": "PWM" + }, + { + "name": "middle", + "ctype": "int16_t", + "desc": "Middle/Neutral servo position (`servoParams(i)->middle`)", + "units": "PWM" + }, + { + "name": "rate", + "ctype": "int8_t", + "desc": "Servo rate/scaling (`servoParams(i)->rate`, -125..125). Encoded as two's complement", + "units": "% (-100 to 100)" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Always 0", + "value": 0 + }, + { + "name": "reserved2", + "ctype": "uint8_t", + "desc": "Always 0", + "value": 0 + }, + { + "name": "legacyForwardChan", + "ctype": "uint8_t", + "desc": "Always 255 (Legacy)", + "value": 255 + }, + { + "name": "legacyReversedSources", + "ctype": "uint32_t", + "desc": "Always 0 (Legacy)", + "value": 0 + } + ], + "repeating": "MAX_SUPPORTED_SERVOS" + }, + "variable_len": "MAX_SUPPORTED_SERVOS", + "notes": "Superseded by `MSP2_INAV_SERVO_CONFIG` which has a cleaner structure.", + "description": "Retrieves the configuration parameters for all supported servos (min, max, middle, rate). Legacy format with unused fields." + }, + "MSP_NAV_STATUS": { + "code": 121, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "navMode", + "ctype": "uint8_t", + "desc": "Enum (`navSystemStatus_Mode_e`): Current navigation mode (None, RTH, NAV, Hold, etc.) (`NAV_Status.mode`)", + "units": "", + "enum": "navSystemStatus_Mode_e" + }, + { + "name": "navState", + "ctype": "uint8_t", + "desc": "Enum (`navSystemStatus_State_e`): Current navigation state (`NAV_Status.state`)", + "units": "", + "enum": "navSystemStatus_State_e" + }, + { + "name": "activeWpAction", + "ctype": "uint8_t", + "desc": "Enum (`navWaypointActions_e`): Action of the currently executing waypoint (`NAV_Status.activeWpAction`)", + "units": "", + "enum": "navWaypointActions_e" + }, + { + "name": "activeWpNumber", + "ctype": "uint8_t", + "desc": "Index: Index of the currently executing waypoint (`NAV_Status.activeWpNumber`)", + "units": "" + }, + { + "name": "navError", + "ctype": "uint8_t", + "desc": "Enum (`navSystemStatus_Error_e`): Current navigation error code (`NAV_Status.error`)", + "units": "", + "enum": "navSystemStatus_Error_e" + }, + { + "name": "targetHeading", + "ctype": "int16_t", + "desc": "Target heading for heading controller (`getHeadingHoldTarget()`)", + "units": "degrees" + } + ] + }, + "notes": "Requires `USE_GPS`.", + "description": "Retrieves the current status of the navigation system." + }, + "MSP_NAV_CONFIG": { + "code": 122, + "mspv": 1, + "not_implemented": true + }, + "MSP_3D": { + "code": 124, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "deadbandLow", + "ctype": "uint16_t", + "desc": "Lower deadband limit for 3D mode (`reversibleMotorsConfig()->deadband_low`)", + "units": "PWM" + }, + { + "name": "deadbandHigh", + "ctype": "uint16_t", + "desc": "Upper deadband limit for 3D mode (`reversibleMotorsConfig()->deadband_high`)", + "units": "PWM" + }, + { + "name": "neutral", + "ctype": "uint16_t", + "desc": "Neutral throttle point for 3D mode (`reversibleMotorsConfig()->neutral`)", + "units": "PWM" + } + ] + }, + "notes": "Requires reversible motor support.", + "description": "Retrieves settings related to 3D/reversible motor operation." + }, + "MSP_RC_DEADBAND": { + "code": 125, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "deadband", + "ctype": "uint8_t", + "desc": "General RC deadband for Roll/Pitch (`rcControlsConfig()->deadband`)", + "units": "PWM" + }, + { + "name": "yawDeadband", + "ctype": "uint8_t", + "desc": "Specific deadband for Yaw (`rcControlsConfig()->yaw_deadband`)", + "units": "PWM" + }, + { + "name": "altHoldDeadband", + "ctype": "uint8_t", + "desc": "Deadband for altitude hold adjustments (`rcControlsConfig()->alt_hold_deadband`)", + "units": "PWM" + }, + { + "name": "throttleDeadband", + "ctype": "uint16_t", + "desc": "Deadband around throttle mid-stick (`rcControlsConfig()->mid_throttle_deadband`)", + "units": "PWM" + } + ] + }, + "notes": "", + "description": "Retrieves RC input deadband settings." + }, + "MSP_SENSOR_ALIGNMENT": { + "code": 126, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "gyroAlign", + "ctype": "uint8_t", + "desc": "Always 0 (Legacy alignment enum)", + "units": "", + "value": 0 + }, + { + "name": "accAlign", + "ctype": "uint8_t", + "desc": "Always 0 (Legacy alignment enum)", + "units": "", + "value": 0 + }, + { + "name": "magAlign", + "ctype": "uint8_t", + "desc": "Magnetometer alignment (`compassConfig()->mag_align`). 0 if `USE_MAG` disabled", + "units": "" + }, + { + "name": "opflowAlign", + "ctype": "uint8_t", + "desc": "Optical flow alignment (`opticalFlowConfig()->opflow_align`). 0 if `USE_OPFLOW` disabled", + "units": "" + } + ] + }, + "notes": "Board alignment is now typically handled by `MSP_BOARD_ALIGNMENT`. This returns legacy enum values where applicable.", + "description": "Retrieves sensor alignment settings (legacy format)." + }, + "MSP_LED_STRIP_MODECOLOR": { + "code": 127, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "modeIndex", + "ctype": "uint8_t", + "desc": "Index of the LED mode Enum (`ledModeIndex_e`). `LED_MODE_COUNT` for special colors", + "units": "", + "enum": "ledModeIndex_e" + }, + { + "name": "directionOrSpecialIndex", + "ctype": "uint8_t", + "desc": "Index of the direction (`ledDirectionId_e`) or special color (`ledSpecialColorIds_e`)", + "units": "" + }, + { + "name": "colorIndex", + "ctype": "uint8_t", + "desc": "Index of the color assigned from `ledStripConfig()->colors`", + "units": "" + } + ], + "repeating": "LED_MODE_COUNT * LED_DIRECTION_COUNT + LED_SPECIAL_COLOR_COUNT" + }, + "variable_len": "LED_MODE_COUNT * LED_DIRECTION_COUNT + LED_SPECIAL_COLOR_COUNT", + "notes": "Only available if `USE_LED_STRIP` is defined. Entries where `modeIndex == LED_MODE_COUNT` describe special colors.", + "description": "Retrieves the color index assigned to each LED mode and function/direction combination, including special colors." + }, + "MSP_BATTERY_STATE": { + "code": 130, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "cellCount", + "ctype": "uint8_t", + "desc": "Number of battery cells (`getBatteryCellCount()`)", + "units": "Count" + }, + { + "name": "capacity", + "ctype": "uint16_t", + "desc": "Battery capacity (`currentBatteryProfile->capacity.value`)", + "units": "mAh" + }, + { + "name": "vbatScaled", + "ctype": "uint8_t", + "desc": "Battery voltage / 10 (`getBatteryVoltage() / 10`)", + "units": "0.1V" + }, + { + "name": "mAhDrawn", + "ctype": "uint16_t", + "desc": "Consumed capacity (`getMAhDrawn()`)", + "units": "mAh" + }, + { + "name": "amperage", + "ctype": "int16_t", + "desc": "Current draw (`getAmperage()`)", + "units": "0.01A" + }, + { + "name": "batteryState", + "ctype": "uint8_t", + "desc": "Enum `batteryState_e` Current battery state (`getBatteryState()`, see `BATTERY_STATE_*`)", + "units": "Enum", + "enum": "batteryState_e" + }, + { + "name": "vbatActual", + "ctype": "uint16_t", + "desc": "Actual battery voltage (`getBatteryVoltage()`)", + "units": "0.01V" + } + ] + }, + "notes": "Only available if `USE_DJI_HD_OSD` or `USE_MSP_DISPLAYPORT` is defined. Some values are duplicated from `MSP_ANALOG` / `MSP2_INAV_ANALOG` but potentially with different scaling/types.", + "description": "Provides battery state information, formatted primarily for DJI FPV Goggles compatibility." + }, + "MSP_VTXTABLE_BAND": { + "code": 137, + "mspv": 1, + "request": null, + "reply": null, + "notes": "The ID is defined, but no handler exists in the provided C code. Likely intended to query band names and frequencies.", + "description": "Retrieves information about a specific VTX band from the VTX table. (Implementation missing in provided `fc_msp.c`)" + }, + "MSP_VTXTABLE_POWERLEVEL": { + "code": 138, + "mspv": 1, + "request": { + "payload": [ + { + "name": "powerLevelIndex", + "ctype": "uint8_t", + "desc": "1-based index of the power level to query", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "powerLevelIndex", + "ctype": "uint8_t", + "desc": "1-based index of the returned power level", + "units": "" + }, + { + "name": "powerValue", + "ctype": "uint16_t", + "desc": "Always 0 (Actual power value in mW is not stored/returned via MSP)", + "units": "", + "value": 0 + }, + { + "name": "labelLength", + "ctype": "uint8_t", + "desc": "Length of the power level label string that follows", + "units": "" + }, + { + "name": "label", + "desc": "Power level label string (e.g., \"25\", \"200\"). Length given by previous field", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_VTX_CONTROL`. Returns error if index is out of bounds. The `powerValue` field is unused.", + "description": "Retrieves information about a specific VTX power level from the VTX table." + }, + "MSP_STATUS_EX": { + "code": 150, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "cycleTime", + "ctype": "uint16_t", + "desc": "Main loop cycle time", + "units": "Β΅s" + }, + { + "name": "i2cErrors", + "ctype": "uint16_t", + "desc": "I2C errors", + "units": "Count" + }, + { + "name": "sensorStatus", + "ctype": "uint16_t", + "desc": "Bitmask: Sensor status", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "activeModesLow", + "ctype": "uint32_t", + "desc": "Bitmask: First 32 active modes", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "profile", + "ctype": "uint8_t", + "desc": "Current config profile index", + "units": "Index" + }, + { + "name": "cpuLoad", + "ctype": "uint16_t", + "desc": "Average system load percentage (`averageSystemLoadPercent`)", + "units": "%" + }, + { + "name": "armingFlags", + "ctype": "uint16_t", + "desc": "Bitmask: Flight controller arming flags (`armingFlags`). Note: Truncated to 16 bits", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "accCalibAxisFlags", + "ctype": "uint8_t", + "desc": "Bitmask: Accelerometer calibrated axes flags (`accGetCalibrationAxisFlags()`)", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "notes": "Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements.", + "description": "Provides extended flight controller status, including CPU load, arming flags, and calibration status, in addition to `MSP_STATUS` fields." + }, + "MSP_SENSOR_STATUS": { + "code": 151, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "overallHealth", + "ctype": "uint8_t", + "desc": "1 if all essential hardware is healthy, 0 otherwise (`isHardwareHealthy()`)", + "units": "Boolean" + }, + { + "name": "gyroStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Gyro hardware status (`getHwGyroStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "accStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Accelerometer hardware status (`getHwAccelerometerStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "magStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Compass hardware status (`getHwCompassStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "baroStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Barometer hardware status (`getHwBarometerStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "gpsStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` GPS hardware status (`getHwGPSStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "rangefinderStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Rangefinder hardware status (`getHwRangefinderStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "pitotStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Pitot hardware status (`getHwPitotmeterStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + }, + { + "name": "opflowStatus", + "ctype": "uint8_t", + "desc": "Enum `hardwareSensorStatus_e` Optical Flow hardware status (`getHwOpticalFlowStatus()`)", + "units": "Enum", + "enum": "hardwareSensorStatus_e" + } + ] + }, + "notes": "Status values map to the `hardwareSensorStatus_e` enum: `HW_SENSOR_NONE`, `HW_SENSOR_OK`, `HW_SENSOR_UNAVAILABLE`, `HW_SENSOR_UNHEALTHY`.", + "description": "Provides the hardware status for each individual sensor system." + }, + "MSP_UID": { + "code": 160, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "uid0", + "ctype": "uint32_t", + "desc": "First 32 bits of the unique ID (`U_ID_0`)", + "units": "" + }, + { + "name": "uid1", + "ctype": "uint32_t", + "desc": "Middle 32 bits of the unique ID (`U_ID_1`)", + "units": "" + }, + { + "name": "uid2", + "ctype": "uint32_t", + "desc": "Last 32 bits of the unique ID (`U_ID_2`)", + "units": "" + } + ] + }, + "notes": "Total 12 bytes, representing a 96-bit unique ID.", + "description": "Provides the unique identifier of the microcontroller." + }, + "MSP_GPSSVINFO": { + "code": 164, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "protocolVersion", + "ctype": "uint8_t", + "desc": "Always 1 (Stub version)", + "units": "", + "value": 1 + }, + { + "name": "numChannels", + "ctype": "uint8_t", + "desc": "Always 0 (Number of SV info channels reported)", + "units": "", + "value": 0 + }, + { + "name": "hdopHundredsDigit", + "ctype": "uint8_t", + "desc": "Hundreds digit of HDOP (stub always writes 0)", + "units": "" + }, + { + "name": "hdopTensDigit", + "ctype": "uint8_t", + "desc": "Tens digit of HDOP (`gpsSol.hdop / 100`, truncated)", + "units": "" + }, + { + "name": "hdopUnitsDigit", + "ctype": "uint8_t", + "desc": "Units digit of HDOP (`gpsSol.hdop / 100`, duplicated by stub)", + "units": "" + } + ] + }, + "notes": "Requires `USE_GPS`. This is just a stub in INAV and does not provide actual per-satellite signal info. HDOP digits are not formatted correctly: tens and units both contain `gpsSol.hdop / 100`.", + "description": "Provides satellite signal strength information (legacy U-Blox compatibility stub)." + }, + "MSP_GPSSTATISTICS": { + "code": 166, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "lastMessageDt", + "ctype": "uint16_t", + "desc": "Time since last valid GPS message (`gpsStats.lastMessageDt`)", + "units": "ms" + }, + { + "name": "errors", + "ctype": "uint32_t", + "desc": "Number of GPS communication errors (`gpsStats.errors`)", + "units": "Count" + }, + { + "name": "timeouts", + "ctype": "uint32_t", + "desc": "Number of GPS communication timeouts (`gpsStats.timeouts`)", + "units": "Count" + }, + { + "name": "packetCount", + "ctype": "uint32_t", + "desc": "Number of valid GPS packets received (`gpsStats.packetCount`)", + "units": "Count" + }, + { + "name": "hdop", + "ctype": "uint16_t", + "desc": "Horizontal Dilution of Precision (`gpsSol.hdop`)", + "units": "HDOP * 100" + }, + { + "name": "eph", + "ctype": "uint16_t", + "desc": "Estimated Horizontal Position Accuracy (`gpsSol.eph`)", + "units": "cm" + }, + { + "name": "epv", + "ctype": "uint16_t", + "desc": "Estimated Vertical Position Accuracy (`gpsSol.epv`)", + "units": "cm" + } + ] + }, + "notes": "Requires `USE_GPS`.", + "description": "Provides debugging statistics for the GPS communication link." + }, + "MSP_OSD_VIDEO_CONFIG": { + "code": 180, + "mspv": 1, + "request": null, + "reply": null, + "name": "MSP_OSD_VIDEO_CONFIG", + "missing": true + }, + "MSP_SET_OSD_VIDEO_CONFIG": { + "code": 181, + "mspv": 1, + "request": null, + "reply": null, + "name": "MSP_SET_OSD_VIDEO_CONFIG", + "missing": true + }, + "MSP_DISPLAYPORT": { + "code": 182, + "mspv": 1, + "request": null, + "reply": null, + "name": "MSP_DISPLAYPORT", + "missing": true + }, + "MSP_SET_TX_INFO": { + "code": 186, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rssi", + "ctype": "uint8_t", + "desc": "RSSI value (0-255) provided by the external source; firmware scales it to 10-bit (`value << 2`)", + "units": "Raw" + } + ] + }, + "reply": null, + "notes": "Calls `setRSSIFromMSP()`. Expects 1 byte.", + "description": "Allows a transmitter LUA script (or similar) to send runtime information (currently only RSSI) to the firmware." + }, + "MSP_TX_INFO": { + "code": 187, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "rssiSource", + "ctype": "uint8_t", + "desc": "Enum: Source of the RSSI value (`getRSSISource()`, see `rssiSource_e`)", + "units": "", + "enum": "rssiSource_e" + }, + { + "name": "rtcDateTimeIsSet", + "ctype": "uint8_t", + "desc": "Boolean: 1 if the RTC has been set, 0 otherwise", + "units": "" + } + ] }, - "dataSize == 1": { - "description": "Query one timer", - "request": { - "payload": [ - { - "name": "timerIndex", - "ctype": "uint8_t", - "desc": "0..HARDWARE_TIMER_DEFINITION_COUNT-1" - } - ] - }, - "reply": { - "payload": [ - { - "name": "timerIndex", - "ctype": "uint8_t", - "desc": "Echoed timer index" - }, - { - "name": "outputMode", - "ctype": "uint8_t", - "enum": "outputMode_e", - "desc": "OUTPUT_MODE_*" - } - ] - } - } - } - }, - "MSP2_INAV_SET_TIMER_OUTPUT_MODE": { - "code": 8207, - "mspv": 2, - "request": { - "payload": [ - { - "name": "timerIndex", - "ctype": "uint8_t", - "desc": "Index of the hardware timer definition", - "units": "" - }, - { - "name": "outputMode", - "ctype": "uint8_t", - "desc": "Output mode override (`outputMode_e` enum) to set", - "units": "", - "enum": "outputMode_e" - } - ] - }, - "reply": null, - "notes": "Only available on non-SITL builds. Expects 2 bytes. Returns error if `timerIndex` is invalid.", - "description": "Set the output mode override for a specific hardware timer." - }, - "MSP2_INAV_MIXER": { - "code": 8208, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "motorDirectionInverted", - "ctype": "uint8_t", - "desc": "Boolean: 1 if motor direction is reversed globally (`mixerConfig()->motorDirectionInverted`)", - "units": "" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Always 0 (Was yaw jump prevention limit)", - "units": "", - "value": 0 - }, - { - "name": "motorStopOnLow", - "ctype": "uint8_t", - "desc": "Boolean: 1 if motors stop at minimum throttle (`mixerConfig()->motorstopOnLow`)", - "units": "" - }, - { - "name": "platformType", - "ctype": "uint8_t", - "desc": "Enum (`mixerConfig()->platformType`)", - "units": "", - "enum": "flyingPlatformType_e" - }, - { - "name": "hasFlaps", - "ctype": "uint8_t", - "desc": "Boolean: 1 if the current mixer configuration includes flaps (`mixerConfig()->hasFlaps`)", - "units": "" - }, - { - "name": "appliedMixerPreset", - "ctype": "int16_t", - "desc": "Enum (`mixerPreset_e`): Mixer preset currently applied (`mixerConfig()->appliedMixerPreset`) WARNING: cannot figure where this is", - "units": "", - "enum": "mixerPreset_e" - }, - { - "name": "maxMotors", - "ctype": "uint8_t", - "desc": "Constant: Maximum motors supported (`MAX_SUPPORTED_MOTORS`)", - "units": "" - }, - { - "name": "maxServos", - "ctype": "uint8_t", - "desc": "Constant: Maximum servos supported (`MAX_SUPPORTED_SERVOS`)", - "units": "" - } - ] - }, - "notes": "", - "description": "Retrieves INAV-specific mixer configuration details." - }, - "MSP2_INAV_SET_MIXER": { - "code": 8209, - "mspv": 2, - "request": { - "payload": [ - { - "name": "motorDirectionInverted", - "ctype": "uint8_t", - "desc": "Sets `mixerConfigMutable()->motorDirectionInverted`", - "units": "" - }, - { - "name": "reserved1", - "ctype": "uint8_t", - "desc": "Ignored", - "units": "" - }, - { - "name": "motorStopOnLow", - "ctype": "uint8_t", - "desc": "Sets `mixerConfigMutable()->motorstopOnLow`", - "units": "" - }, - { - "name": "platformType", - "ctype": "uint8_t", - "desc": "Sets `mixerConfigMutable()->platformType`", - "units": "", - "enum": "flyingPlatformType_e" - }, - { - "name": "hasFlaps", - "ctype": "uint8_t", - "desc": "Sets `mixerConfigMutable()->hasFlaps`", - "units": "" - }, - { - "name": "appliedMixerPreset", - "ctype": "int16_t", - "desc": "Sets `mixerConfigMutable()->appliedMixerPreset`", - "units": "" - }, - { - "name": "maxMotors", - "ctype": "uint8_t", - "desc": "Ignored", - "units": "" - }, - { - "name": "maxServos", - "ctype": "uint8_t", - "desc": "Ignored", - "units": "" - } - ] + "notes": "See `rssiSource_e`.", + "description": "Provides information potentially useful for transmitter LUA scripts." }, - "reply": null, - "notes": "Expects 9 bytes. Calls `mixerUpdateStateFlags()`.", - "description": "Sets INAV-specific mixer configuration details." - }, - "MSP2_INAV_OSD_LAYOUTS": { - "code": 8210, - "mspv": 2, - "request": null, - "reply": null, - "variants": { - "dataSize == 0": { - "description": "Query layout/item counts", - "request": null, - "reply": { - "payload": [ - { - "name": "layoutCount", - "ctype": "uint8_t", - "desc": "Number of OSD layouts (`OSD_LAYOUT_COUNT`)" - }, - { - "name": "itemCount", - "ctype": "uint8_t", - "desc": "Number of OSD items per layout (`OSD_ITEM_COUNT`)" - } - ] - } + "MSP_SET_RAW_RC": { + "code": 200, + "mspv": 1, + "request": { + "payload": [ + { + "name": "rcChannels", + "desc": "Array of RC channel values (typically 1000-2000). Number of channels determined by payload size", + "ctype": "uint16_t", + "array": true, + "array_size": 0, + "units": "PWM" + } + ] }, - "dataSize == 1": { - "description": "Fetch all item positions for a layout", - "request": { - "payload": [ - { - "name": "layoutIndex", - "ctype": "uint8_t", - "desc": "Layout index (0 to `OSD_LAYOUT_COUNT - 1`)" - } - ] - }, - "reply": { - "payload": [ - { - "name": "itemPosition", - "ctype": "uint16_t", - "desc": "Packed X/Y position (`osdLayoutsConfig()->item_pos[layoutIndex][item]`)", - "units": "packed coords" - } - ], - "repeating": "OSD_ITEM_COUNT" - } + "reply": null, + "variable_len": true, + "notes": "Requires `USE_RX_MSP`. Maximum channels `MAX_SUPPORTED_RC_CHANNEL_COUNT`. Calls `rxMspFrameReceive()`.", + "description": "Provides raw RC channel data to the flight controller, typically used when the receiver is connected via MSP (e.g., MSP RX feature)." + }, + "MSP_SET_RAW_GPS": { + "code": 201, + "mspv": 1, + "request": { + "payload": [ + { + "name": "fixType", + "ctype": "uint8_t", + "desc": "Enum `gpsFixType_e` GPS fix type", + "units": "Enum", + "enum": "gpsFixType_e" + }, + { + "name": "numSat", + "ctype": "uint8_t", + "desc": "Number of satellites", + "units": "Count" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude", + "units": "deg * 1e7" + }, + { + "name": "altitude", + "ctype": "uint16_t", + "desc": "Altitude in meters (converted to centimeters internally; limited to 0-65535 m)", + "units": "m" + }, + { + "name": "speed", + "ctype": "uint16_t", + "desc": "Ground speed (`gpsSol.groundSpeed`)", + "units": "cm/s" + } + ] }, - "dataSize == 3": { - "description": "Fetch a single item position", - "request": { - "payload": [ - { - "name": "layoutIndex", - "ctype": "uint8_t", - "desc": "Layout index (0 to `OSD_LAYOUT_COUNT - 1`)" - }, - { - "name": "itemIndex", - "ctype": "uint16_t", - "desc": "OSD item index (0 to `OSD_ITEM_COUNT - 1`)" - } - ] - }, - "reply": { - "payload": [ - { - "name": "itemPosition", - "ctype": "uint16_t", - "desc": "Packed X/Y position (`osdLayoutsConfig()->item_pos[layoutIndex][itemIndex]`)", - "units": "packed coords" - } - ] - } - } - }, - "notes": "Requires `USE_OSD`. Returns `MSP_RESULT_ACK` on success, `MSP_RESULT_ERROR` if indexes are out of range.", - "description": "Retrieves OSD layout metadata or item positions for specific layouts/items." - }, - "MSP2_INAV_OSD_SET_LAYOUT_ITEM": { - "code": 8211, - "mspv": 2, - "request": { - "payload": [ - { - "name": "layoutIndex", - "ctype": "uint8_t", - "desc": "Index of the OSD layout (0 to `OSD_LAYOUT_COUNT - 1`)", - "units": "Index" - }, - { - "name": "itemIndex", - "ctype": "uint8_t", - "desc": "Index of the OSD item", - "units": "Index" - }, - { - "name": "itemPosition", - "ctype": "uint16_t", - "desc": "Packed X/Y position using `OSD_POS(x, y)` with `OSD_VISIBLE_FLAG` bit", - "units": "Coordinates" - } - ] - }, - "reply": null, - "notes": "Requires `USE_OSD`. Expects 4 bytes. Returns error if indexes are invalid. If the modified layout is not the currently active one, it temporarily overrides the active layout for 10 seconds to show the change. Otherwise, triggers a full OSD redraw.", - "description": "Sets the position of a single OSD item within a specific layout." - }, - "MSP2_INAV_OSD_ALARMS": { - "code": 8212, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "rssiAlarm", - "ctype": "uint8_t", - "desc": "RSSI alarm threshold (`osdConfig()->rssi_alarm`)", - "units": "%" - }, - { - "name": "timerAlarm", - "ctype": "uint16_t", - "desc": "Timer alarm threshold (`osdConfig()->time_alarm`)", - "units": "seconds" - }, - { - "name": "altAlarm", - "ctype": "uint16_t", - "desc": "Altitude alarm threshold (`osdConfig()->alt_alarm`)", - "units": "meters" - }, - { - "name": "distAlarm", - "ctype": "uint16_t", - "desc": "Distance alarm threshold (`osdConfig()->dist_alarm`)", - "units": "meters" - }, - { - "name": "negAltAlarm", - "ctype": "uint16_t", - "desc": "Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`)", - "units": "meters" - }, - { - "name": "gForceAlarm", - "ctype": "uint16_t", - "desc": "G-force alarm threshold (`osdConfig()->gforce_alarm * 1000`)", - "units": "G * 1000" - }, - { - "name": "gForceAxisMinAlarm", - "ctype": "int16_t", - "desc": "Min G-force per-axis alarm (`osdConfig()->gforce_axis_alarm_min * 1000`)", - "units": "G * 1000" - }, - { - "name": "gForceAxisMaxAlarm", - "ctype": "int16_t", - "desc": "Max G-force per-axis alarm (`osdConfig()->gforce_axis_alarm_max * 1000`)", - "units": "G * 1000" - }, - { - "name": "currentAlarm", - "ctype": "uint8_t", - "desc": "Current draw alarm threshold (`osdConfig()->current_alarm`)", - "units": "A" - }, - { - "name": "imuTempMinAlarm", - "ctype": "int16_t", - "desc": "Min IMU temperature alarm (`osdConfig()->imu_temp_alarm_min`)", - "units": "degrees C" - }, - { - "name": "imuTempMaxAlarm", - "ctype": "int16_t", - "desc": "Max IMU temperature alarm (`osdConfig()->imu_temp_alarm_max`)", - "units": "degrees C" - }, - { - "name": "baroTempMinAlarm", - "ctype": "int16_t", - "desc": "Min Baro temperature alarm (`osdConfig()->baro_temp_alarm_min`). 0 if `USE_BARO` disabled", - "units": "degrees C" - }, - { - "name": "baroTempMaxAlarm", - "ctype": "int16_t", - "desc": "Max Baro temperature alarm (`osdConfig()->baro_temp_alarm_max`). 0 if `USE_BARO` disabled", - "units": "degrees C" - }, - { - "name": "adsbWarnDistance", - "ctype": "uint16_t", - "desc": "ADSB warning distance (`osdConfig()->adsb_distance_warning`). 0 if `USE_ADSB` disabled", - "units": "meters" - }, - { - "name": "adsbAlertDistance", - "ctype": "uint16_t", - "desc": "ADSB alert distance (`osdConfig()->adsb_distance_alert`). 0 if `USE_ADSB` disabled", - "units": "meters" - } - ] - }, - "notes": "Requires `USE_OSD`.", - "description": "Retrieves OSD alarm threshold settings." - }, - "MSP2_INAV_OSD_SET_ALARMS": { - "code": 8213, - "mspv": 2, - "request": { - "payload": [ - { - "name": "rssiAlarm", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->rssi_alarm", - "units": "%" - }, - { - "name": "timerAlarm", - "ctype": "uint16_t", - "desc": "Sets `osdConfigMutable()->time_alarm", - "units": "seconds" - }, - { - "name": "altAlarm", - "ctype": "uint16_t", - "desc": "Sets `osdConfigMutable()->alt_alarm", - "units": "meters" - }, - { - "name": "distAlarm", - "ctype": "uint16_t", - "desc": "Sets `osdConfigMutable()->dist_alarm", - "units": "meters" - }, - { - "name": "negAltAlarm", - "ctype": "uint16_t", - "desc": "Sets `osdConfigMutable()->neg_alt_alarm`", - "units": "meters" - }, - { - "name": "gForceAlarm", - "ctype": "uint16_t", - "desc": "Sets `osdConfigMutable()->gforce_alarm = value / 1000.0f`", - "units": "G * 1000" - }, - { - "name": "gForceAxisMinAlarm", - "ctype": "int16_t", - "desc": "Sets `osdConfigMutable()->gforce_axis_alarm_min = value / 1000.0f`", - "units": "G * 1000" - }, - { - "name": "gForceAxisMaxAlarm", - "ctype": "int16_t", - "desc": "Sets `osdConfigMutable()->gforce_axis_alarm_max = value / 1000.0f`", - "units": "G * 1000" - }, - { - "name": "currentAlarm", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->current_alarm`", - "units": "A" - }, - { - "name": "imuTempMinAlarm", - "ctype": "int16_t", - "desc": "Sets `osdConfigMutable()->imu_temp_alarm_min`", - "units": "degrees C" - }, - { - "name": "imuTempMaxAlarm", - "ctype": "int16_t", - "desc": "Sets `osdConfigMutable()->imu_temp_alarm_max`", - "units": "degrees C" - }, - { - "name": "baroTempMinAlarm", - "ctype": "int16_t", - "desc": "Sets `osdConfigMutable()->baro_temp_alarm_min` (if `USE_BARO`)", - "units": "degrees C" - }, - { - "name": "baroTempMaxAlarm", - "ctype": "int16_t", - "desc": "Sets `osdConfigMutable()->baro_temp_alarm_max` (if `USE_BARO`)", - "units": "degrees C" - } - ] - }, - "reply": null, - "notes": "Requires `USE_OSD`. Expects 24 bytes. ADSB alarms are not settable via this message.", - "description": "Sets OSD alarm threshold settings." - }, - "MSP2_INAV_OSD_PREFERENCES": { - "code": 8214, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "videoSystem", - "ctype": "uint8_t", - "desc": "Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`)", - "units": "", - "enum": "videoSystem_e" - }, - { - "name": "mainVoltageDecimals", - "ctype": "uint8_t", - "desc": "Count: Decimal places for main voltage display (`osdConfig()->main_voltage_decimals`)", - "units": "" - }, - { - "name": "ahiReverseRoll", - "ctype": "uint8_t", - "desc": "Boolean: Reverse roll direction on Artificial Horizon (`osdConfig()->ahi_reverse_roll`)", - "units": "" - }, - { - "name": "crosshairsStyle", - "ctype": "uint8_t", - "desc": "Enum `osd_crosshairs_style_e`: Style of the center crosshairs (`osdConfig()->crosshairs_style`)", - "units": "", - "enum": "osd_crosshairs_style_e" - }, - { - "name": "leftSidebarScroll", - "ctype": "uint8_t", - "desc": "Enum `osd_sidebar_scroll_e`: Left sidebar scroll behavior (`osdConfig()->left_sidebar_scroll`)", - "units": "", - "enum": "osd_sidebar_scroll_e" - }, - { - "name": "rightSidebarScroll", - "ctype": "uint8_t", - "desc": "Enum `osd_sidebar_scroll_e`: Right sidebar scroll behavior (`osdConfig()->right_sidebar_scroll`)", - "units": "", - "enum": "osd_sidebar_scroll_e" - }, - { - "name": "sidebarScrollArrows", - "ctype": "uint8_t", - "desc": "Boolean: Show arrows for scrollable sidebars (`osdConfig()->sidebar_scroll_arrows`)", - "units": "" - }, - { - "name": "units", - "ctype": "uint8_t", - "desc": "Enum: `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`)", - "units": "", - "enum": "osd_unit_e" - }, - { - "name": "statsEnergyUnit", - "ctype": "uint8_t", - "desc": "Enum `osd_stats_energy_unit_e`: Unit for energy display in post-flight stats (`osdConfig()->stats_energy_unit`)", - "units": "", - "enum": "osd_stats_energy_unit_e" - } - ] + "reply": null, + "notes": "Requires `USE_GPS`. Expects 14 bytes. Updates `gpsSol` structure and calls `onNewGPSData()`. Note the altitude unit mismatch (meters in MSP, cm internal). Does not provide velocity components.", + "description": "Provides raw GPS data to the flight controller, typically for simulation or external GPS injection." + }, + "MSP_SET_BOX": { + "code": 203, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`. Mode changes are typically handled via RC channels (`MSP_MODE_RANGES`).", + "description": "Sets the state of flight modes (boxes). (Likely unused/obsolete in INAV)." + }, + "MSP_SET_RC_TUNING": { + "code": 204, + "mspv": 1, + "request": { + "payload": [ + { + "name": "legacyRcRate", + "ctype": "uint8_t", + "desc": "Ignored", + "units": "" + }, + { + "name": "rcExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rcExpo8`", + "units": "" + }, + { + "name": "rollRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_ROLL]` (constrained)", + "units": "" + }, + { + "name": "pitchRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_PITCH]` (constrained)", + "units": "" + }, + { + "name": "yawRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_YAW]` (constrained)", + "units": "" + }, + { + "name": "dynamicThrottlePID", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->throttle.dynPID` (constrained)", + "units": "" + }, + { + "name": "throttleMid", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->throttle.rcMid8`", + "units": "" + }, + { + "name": "throttleExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->throttle.rcExpo8`", + "units": "" + }, + { + "name": "tpaBreakpoint", + "ctype": "uint16_t", + "desc": "Sets `currentControlRateProfile->throttle.pa_breakpoint`", + "units": "" + }, + { + "name": "rcYawExpo", + "ctype": "uint8_t", + "desc": "(Optional) Sets `currentControlRateProfile->stabilized.rcYawExpo8`", + "units": "", + "optional": true + } + ] + }, + "reply": null, + "notes": "Expects 10 or 11 bytes. Calls `schedulePidGainsUpdate()`. Superseded by `MSP2_INAV_SET_RATE_PROFILE`.", + "description": "Sets RC tuning parameters (rates, expos, TPA) for the current control rate profile." + }, + "MSP_ACC_CALIBRATION": { + "code": 205, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Will fail if armed. Calls `accStartCalibration()`.", + "description": "Starts the accelerometer calibration procedure." + }, + "MSP_MAG_CALIBRATION": { + "code": 206, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Will fail if armed. Enables the `CALIBRATE_MAG` state flag.", + "description": "Starts the magnetometer calibration procedure." + }, + "MSP_SET_MISC": { + "code": 207, + "mspv": 1, + "request": { + "payload": [ + { + "name": "midRc", + "ctype": "uint16_t", + "desc": "Ignored", + "units": "PWM" + }, + { + "name": "legacyMinThrottle", + "ctype": "uint16_t", + "desc": "Ignored" + }, + { + "name": "legacyMaxThrottle", + "ctype": "uint16_t", + "desc": "Ignored" + }, + { + "name": "minCommand", + "ctype": "uint16_t", + "desc": "Sets `motorConfigMutable()->mincommand` (constrained 0-PWM_RANGE_MAX)", + "units": "PWM" + }, + { + "name": "failsafeThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->failsafe_throttle` (constrained PWM_RANGE_MIN/MAX)", + "units": "PWM" + }, + { + "name": "gpsType", + "ctype": "uint8_t", + "desc": "Enum `gpsProvider_e` (Sets `gpsConfigMutable()->provider`)", + "units": "Enum", + "enum": "gpsProvider_e" + }, + { + "name": "legacyGpsBaud", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "gpsSbasMode", + "ctype": "uint8_t", + "desc": "Enum `sbasMode_e` (Sets `gpsConfigMutable()->sbasMode`)", + "units": "Enum", + "enum": "sbasMode_e" + }, + { + "name": "legacyMwCurrentOut", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "rssiChannel", + "ctype": "uint8_t", + "desc": "Sets `rxConfigMutable()->rssi_channel` (constrained 0-MAX_SUPPORTED_RC_CHANNEL_COUNT). Updates source", + "units": "Index" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "magDeclination", + "ctype": "uint16_t", + "desc": "Sets `compassConfigMutable()->mag_declination = value * 10` (if `USE_MAG`)", + "units": "0.1 degrees" + }, + { + "name": "vbatScale", + "ctype": "uint8_t", + "desc": "Sets `batteryMetersConfigMutable()->voltage.scale = value * 10` (if `USE_ADC`)", + "units": "Scale / 10" + }, + { + "name": "vbatMinCell", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin = value * 10` (if `USE_ADC`)", + "units": "0.1V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax = value * 10` (if `USE_ADC`)", + "units": "0.1V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning = value * 10` (if `USE_ADC`)", + "units": "0.1V" + } + ] + }, + "reply": null, + "notes": "Expects 22 bytes. Superseded by `MSP2_INAV_SET_MISC`.", + "description": "Sets miscellaneous configuration settings (legacy formats/scaling)." + }, + "MSP_RESET_CONF": { + "code": 208, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Will fail if armed. Suspends RX, calls `resetEEPROM()`, `writeEEPROM()`, `readEEPROM()`, resumes RX. Use with caution!", + "description": "Resets all configuration settings to their default values and saves to EEPROM." + }, + "MSP_SET_WP": { + "code": 209, + "mspv": 1, + "request": { + "payload": [ + { + "name": "waypointIndex", + "ctype": "uint8_t", + "desc": "Index of the waypoint to set (0 to `NAV_MAX_WAYPOINTS - 1`)", + "units": "Index" + }, + { + "name": "action", + "ctype": "uint8_t", + "desc": "Enum `navWaypointActions_e` Waypoint action type", + "units": "Enum", + "enum": "navWaypointActions_e" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude coordinate", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude coordinate", + "units": "deg * 1e7" + }, + { + "name": "altitude", + "ctype": "int32_t", + "desc": "Altitude coordinate", + "units": "cm" + }, + { + "name": "param1", + "ctype": "uint16_t", + "desc": "Parameter 1", + "units": "Varies" + }, + { + "name": "param2", + "ctype": "uint16_t", + "desc": "Parameter 2", + "units": "Varies" + }, + { + "name": "param3", + "ctype": "uint16_t", + "desc": "Parameter 3", + "units": "Varies" + }, + { + "name": "flag", + "ctype": "uint8_t", + "desc": "Bitmask: Waypoint flags (`navWaypointFlags_e`)", + "units": "Bitmask", + "bitmask": true, + "enum": "navWaypointFlags_e" + } + ] + }, + "reply": null, + "notes": "Expects 21 bytes. Calls `setWaypoint()`. If `USE_FW_AUTOLAND` is enabled, this also interacts with autoland approach settings based on waypoint index and flags.", + "description": "Sets a single waypoint in the mission plan." }, - "notes": "Requires `USE_OSD`.", - "description": "Retrieves OSD display preferences (video system, units, styles, etc.)." - }, - "MSP2_INAV_OSD_SET_PREFERENCES": { - "code": 8215, - "mspv": 2, - "request": { - "payload": [ - { - "name": "videoSystem", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->video_system`", - "units": "", - "enum": "videoSystem_e" - }, - { - "name": "mainVoltageDecimals", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->main_voltage_decimals`", - "units": "" - }, - { - "name": "ahiReverseRoll", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->ahi_reverse_roll`", - "units": "" - }, - { - "name": "crosshairsStyle", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->crosshairs_style`", - "units": "", - "enum": "osd_crosshairs_style_e" - }, - { - "name": "leftSidebarScroll", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->left_sidebar_scroll`", - "units": "", - "enum": "osd_sidebar_scroll_e" - }, - { - "name": "rightSidebarScroll", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->right_sidebar_scroll`", - "units": "", - "enum": "osd_sidebar_scroll_e" - }, - { - "name": "sidebarScrollArrows", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->sidebar_scroll_arrows`", - "units": "" - }, - { - "name": "units", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->units` (enum `osd_unit_e`)", - "units": "", - "enum": "osd_unit_e" - }, - { - "name": "statsEnergyUnit", - "ctype": "uint8_t", - "desc": "Sets `osdConfigMutable()->stats_energy_unit`", - "units": "", - "enum": "osd_stats_energy_unit_e" - } - ] + "MSP_SELECT_SETTING": { + "code": 210, + "mspv": 1, + "request": { + "payload": [ + { + "name": "profileIndex", + "ctype": "uint8_t", + "desc": "Index of the profile to activate (0-based)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Will fail if armed. Calls `setConfigProfileAndWriteEEPROM()`.", + "description": "Selects the active configuration profile and saves it." }, - "reply": null, - "notes": "Requires `USE_OSD`. Expects 9 bytes. Triggers a full OSD redraw.", - "description": "Sets OSD display preferences." - }, - "MSP2_INAV_SELECT_BATTERY_PROFILE": { - "code": 8216, - "mspv": 2, - "request": { - "payload": [ - { - "name": "batteryProfileIndex", - "ctype": "uint8_t", - "desc": "Index of the battery profile to activate (0-based)", - "units": "" - } - ] + "MSP_SET_HEAD": { + "code": 211, + "mspv": 1, + "request": { + "payload": [ + { + "name": "heading", + "ctype": "uint16_t", + "desc": "Target heading (0-359)", + "units": "degrees" + } + ] + }, + "reply": null, + "notes": "Expects 2 bytes. Calls `updateHeadingHoldTarget()`.", + "description": "Sets the target heading for the heading hold controller (e.g., during MAG mode)." }, - "reply": null, - "notes": "Expects 1 byte. Will fail if armed. Calls `setConfigBatteryProfileAndWriteEEPROM()`.", - "description": "Selects the active battery profile and saves configuration." - }, - "MSP2_INAV_DEBUG": { - "code": 8217, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "debugValues", - "desc": "Values from the `debug` array (signed, typically 8 entries)", - "ctype": "int32_t", - "array": true, - "array_size": 8, - "array_size_define": "DEBUG32_VALUE_COUNT", - "units": "" - } - ] + "MSP_SET_SERVO_CONFIGURATION": { + "code": 212, + "mspv": 1, + "request": { + "payload": [ + { + "name": "servoIndex", + "ctype": "uint8_t", + "desc": "Index of the servo to configure (0 to `MAX_SUPPORTED_SERVOS - 1`)", + "units": "Index" + }, + { + "name": "min", + "ctype": "uint16_t", + "desc": "Minimum servo endpoint", + "units": "PWM" + }, + { + "name": "max", + "ctype": "uint16_t", + "desc": "Maximum servo endpoint", + "units": "PWM" + }, + { + "name": "middle", + "ctype": "uint16_t", + "desc": "Middle/Neutral servo position", + "units": "PWM" + }, + { + "name": "rate", + "ctype": "uint8_t", + "desc": "Servo rate/scaling", + "units": "%" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "reserved2", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "legacyForwardChan", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "legacyReversedSources", + "ctype": "uint32_t", + "desc": "Ignored" + } + ] + }, + "reply": null, + "notes": "Expects 15 bytes. Returns error if index is invalid. Calls `servoComputeScalingFactors()`. Superseded by `MSP2_INAV_SET_SERVO_CONFIG`.", + "description": "Sets the configuration for a single servo (legacy format)." }, - "variable_len": true, - "notes": "`DEBUG32_VALUE_COUNT` is usually 8.", - "description": "Retrieves values from the firmware's 32-bit `debug[]` array. Supersedes `MSP_DEBUG`." - }, - "MSP2_BLACKBOX_CONFIG": { - "code": 8218, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "blackboxSupported", - "ctype": "uint8_t", - "desc": "Boolean: 1 if Blackbox is supported (`USE_BLACKBOX`), 0 otherwise", - "units": "" - }, - { - "name": "blackboxDevice", - "ctype": "uint8_t", - "desc": "Enum `BlackboxDevice`: Target device for logging (`blackboxConfig()->device`). 0 if not supported", - "units": "", - "enum": "BlackboxDevice" - }, - { - "name": "blackboxRateNum", - "ctype": "uint16_t", - "desc": "Numerator for logging rate divider (`blackboxConfig()->rate_num`). 0 if not supported", - "units": "" - }, - { - "name": "blackboxRateDenom", - "ctype": "uint16_t", - "desc": "Denominator for logging rate divider (`blackboxConfig()->rate_denom`). 0 if not supported", - "units": "" - }, - { - "name": "blackboxIncludeFlags", - "ctype": "uint32_t", - "desc": "Bitmask: Flags for fields included/excluded from logging (`blackboxConfig()->includeFlags`)", - "units": "", - "bitmask": true - } - ] + "MSP_SET_MOTOR": { + "code": 214, + "mspv": 1, + "request": { + "payload": [ + { + "name": "motorValues", + "desc": "Array of motor values to set when disarmed. Only affects first `MAX_SUPPORTED_MOTORS` entries", + "ctype": "uint16_t", + "array": true, + "array_size": 8, + "units": "PWM" + } + ] + }, + "reply": null, + "notes": "Expects 16 bytes. Modifies the `motor_disarmed` array. These values are *not* saved persistently.", + "description": "Sets the disarmed motor values, typically used for motor testing or propeller balancing functions in a configurator." + }, + "MSP_SET_NAV_CONFIG": { + "code": 215, + "mspv": 1, + "not_implemented": true + }, + "MSP_SET_3D": { + "code": 217, + "mspv": 1, + "request": { + "payload": [ + { + "name": "deadbandLow", + "ctype": "uint16_t", + "desc": "Sets `reversibleMotorsConfigMutable()->deadband_low`", + "units": "PWM" + }, + { + "name": "deadbandHigh", + "ctype": "uint16_t", + "desc": "Sets `reversibleMotorsConfigMutable()->deadband_high`", + "units": "PWM" + }, + { + "name": "neutral", + "ctype": "uint16_t", + "desc": "Sets `reversibleMotorsConfigMutable()->neutral`", + "units": "PWM" + } + ] + }, + "reply": null, + "notes": "Expects 6 bytes. Requires reversible motor support.", + "description": "Sets parameters related to 3D/reversible motor operation." }, - "notes": "If `USE_BLACKBOX` is disabled, only the first four fields are returned (all zero).", - "description": "Retrieves the Blackbox configuration. Supersedes `MSP_BLACKBOX_CONFIG`." - }, - "MSP2_SET_BLACKBOX_CONFIG": { - "code": 8219, - "mspv": 2, - "request": { - "payload": [ - { - "name": "blackboxDevice", - "ctype": "uint8_t", - "desc": "Sets `blackboxConfigMutable()->device`", - "units": "", - "enum": "BlackboxDevice" - }, - { - "name": "blackboxRateNum", - "ctype": "uint16_t", - "desc": "Sets `blackboxConfigMutable()->rate_num`", - "units": "" - }, - { - "name": "blackboxRateDenom", - "ctype": "uint16_t", - "desc": "Sets `blackboxConfigMutable()->rate_denom`", - "units": "" - }, - { - "name": "blackboxIncludeFlags", - "ctype": "uint32_t", - "desc": "Sets `blackboxConfigMutable()->includeFlags`", - "units": "" - } - ] + "MSP_SET_RC_DEADBAND": { + "code": 218, + "mspv": 1, + "request": { + "payload": [ + { + "name": "deadband", + "ctype": "uint8_t", + "desc": "Sets `rcControlsConfigMutable()->deadband`", + "units": "PWM" + }, + { + "name": "yawDeadband", + "ctype": "uint8_t", + "desc": "Sets `rcControlsConfigMutable()->yaw_deadband`", + "units": "PWM" + }, + { + "name": "altHoldDeadband", + "ctype": "uint8_t", + "desc": "Sets `rcControlsConfigMutable()->alt_hold_deadband`", + "units": "PWM" + }, + { + "name": "throttleDeadband", + "ctype": "uint16_t", + "desc": "Sets `rcControlsConfigMutable()->mid_throttle_deadband`", + "units": "PWM" + } + ] + }, + "reply": null, + "notes": "Expects 5 bytes.", + "description": "Sets RC input deadband values." + }, + "MSP_SET_RESET_CURR_PID": { + "code": 219, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Calls `PG_RESET_CURRENT(pidProfile)`. To save, follow with `MSP_EEPROM_WRITE`.", + "description": "Resets the PIDs of the *current* profile to their default values. Does not save." + }, + "MSP_SET_SENSOR_ALIGNMENT": { + "code": 220, + "mspv": 1, + "request": { + "payload": [ + { + "name": "gyroAlign", + "ctype": "uint8_t", + "desc": "Ignored", + "units": "" + }, + { + "name": "accAlign", + "ctype": "uint8_t", + "desc": "Ignored", + "units": "" + }, + { + "name": "magAlign", + "ctype": "uint8_t", + "desc": "Sets `compassConfigMutable()->mag_align` (if `USE_MAG`)", + "units": "" + }, + { + "name": "opflowAlign", + "ctype": "uint8_t", + "desc": "Sets `opticalFlowConfigMutable()->opflow_align` (if `USE_OPFLOW`)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 4 bytes. Use `MSP_SET_BOARD_ALIGNMENT` for primary board orientation.", + "description": "Sets sensor alignment (legacy format)." }, - "reply": null, - "notes": "Requires `USE_BLACKBOX`. Expects 9 bytes. Returns error if Blackbox is currently logging (`!blackboxMayEditConfig()`).", - "description": "Sets the Blackbox configuration. Supersedes `MSP_SET_BLACKBOX_CONFIG`." - }, - "MSP2_INAV_TEMP_SENSOR_CONFIG": { - "code": 8220, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "type", - "ctype": "uint8_t", - "desc": "Enum (`tempSensorType_e`): Type of the temperature sensor", - "units": "", - "enum": "tempSensorType_e" - }, - { - "name": "address", - "ctype": "uint64_t", - "desc": "Sensor address/ID (e.g., for 1-Wire sensors)", - "units": "" - }, - { - "name": "alarmMin", - "ctype": "int16_t", - "desc": "Min temperature alarm threshold (`sensorConfig->alarm_min`)", - "units": "0.1Β°C" - }, - { - "name": "alarmMax", - "ctype": "int16_t", - "desc": "Max temperature alarm threshold (`sensorConfig->alarm_max`)", - "units": "0.1Β°C" - }, - { - "name": "osdSymbol", - "ctype": "uint8_t", - "desc": "Index: OSD symbol to use for this sensor (0 to `TEMP_SENSOR_SYM_COUNT`)", - "units": "" - }, - { - "name": "label", - "desc": "User-defined label for the sensor", - "ctype": "char", - "array": true, - "array_size": 4, - "array_size_define": "TEMPERATURE_LABEL_LEN", - "units": "" - } - ], - "repeating": "MAX_TEMP_SENSORS" + "MSP_SET_LED_STRIP_MODECOLOR": { + "code": 221, + "mspv": 1, + "request": { + "payload": [ + { + "name": "modeIndex", + "ctype": "uint8_t", + "desc": "Index of the LED mode (`ledModeIndex_e` or `LED_MODE_COUNT` for special)", + "units": "" + }, + { + "name": "directionOrSpecialIndex", + "ctype": "uint8_t", + "desc": "Index of the direction (`ledDirectionId_e`) or special color (`ledSpecialColorIds_e`)", + "units": "" + }, + { + "name": "colorIndex", + "ctype": "uint8_t", + "desc": "Index of the color to assign from `ledStripConfig()->colors`", + "units": "" + } + ] + }, + "reply": null, + "notes": "Only available if `USE_LED_STRIP` is defined. Expects 3 bytes. Returns error if setting fails (invalid index).", + "description": "Sets the color index for a specific LED mode/function combination." + }, + "MSP_SET_ACC_TRIM": { + "code": 239, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`. Use `MSP_ACC_CALIBRATION`.", + "description": "Sets the accelerometer trim values (leveling calibration)." + }, + "MSP_ACC_TRIM": { + "code": 240, + "mspv": 1, + "not_implemented": true, + "request": null, + "reply": null, + "notes": "Not implemented in INAV `fc_msp.c`. Calibration data via `MSP_CALIBRATION_DATA`.", + "description": "Gets the accelerometer trim values." + }, + "MSP_SERVO_MIX_RULES": { + "code": 241, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "targetChannel", + "ctype": "uint8_t", + "desc": "Servo output channel index (0-based)", + "units": "Index" + }, + { + "name": "inputSource", + "ctype": "uint8_t", + "desc": "Enum `inputSource_e` Input source for the mix (RC chan, Roll, Pitch...)", + "units": "Enum", + "enum": "inputSource_e" + }, + { + "name": "rate", + "ctype": "int16_t", + "desc": "Mixing rate/weight (`-1000` to `+1000`, percent with sign)", + "units": "%" + }, + { + "name": "speed", + "ctype": "uint8_t", + "desc": "Speed/Slew rate limit (`0`=instant, higher slows response)", + "units": "0-255" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Always 0", + "value": 0 + }, + { + "name": "legacyMax", + "ctype": "uint8_t", + "desc": "Always 100 (Legacy)", + "value": 100 + }, + { + "name": "legacyBox", + "ctype": "uint8_t", + "desc": "Always 0 (Legacy)", + "value": 0 + } + ], + "repeating": "MAX_SERVO_RULES" + }, + "variable_len": "MAX_SERVO_RULES", + "notes": "Superseded by `MSP2_INAV_SERVO_MIXER`.", + "description": "Retrieves the custom servo mixer rules (legacy format)." }, - "variable_len": "MAX_TEMP_SENSORS", - "notes": "Requires `USE_TEMPERATURE_SENSOR`.", - "description": "Retrieves the configuration for all onboard temperature sensors." - }, - "MSP2_INAV_SET_TEMP_SENSOR_CONFIG": { - "code": 8221, - "mspv": 2, - "request": { - "payload": [ - { - "name": "type", - "ctype": "uint8_t", - "desc": "Sets sensor type (`tempSensorType_e`)", - "units": "", - "enum": "tempSensorType_e" - }, - { - "name": "address", - "ctype": "uint64_t", - "desc": "Sets sensor address/ID", - "units": "" - }, - { - "name": "alarmMin", - "ctype": "int16_t", - "desc": "Sets min alarm threshold (`tempSensorConfigMutable(index)->alarm_min`)", - "units": "0.1Β°C" - }, - { - "name": "alarmMax", - "ctype": "int16_t", - "desc": "Sets max alarm threshold (`tempSensorConfigMutable(index)->alarm_max`)", - "units": "0.1Β°C" - }, - { - "name": "osdSymbol", - "ctype": "uint8_t", - "desc": "Sets OSD symbol index (validated)", - "units": "" - }, - { - "name": "label", - "desc": "Sets sensor label (converted to uppercase)", - "ctype": "char", - "array": true, - "array_size": 4, - "array_size_define": "TEMPERATURE_LABEL_LEN", - "units": "" - } - ], - "repeating": "MAX_TEMP_SENSORS" + "MSP_SET_SERVO_MIX_RULE": { + "code": 242, + "mspv": 1, + "request": { + "payload": [ + { + "name": "ruleIndex", + "ctype": "uint8_t", + "desc": "Index of the rule to set (0 to `MAX_SERVO_RULES - 1`)", + "units": "Index" + }, + { + "name": "targetChannel", + "ctype": "uint8_t", + "desc": "Servo output channel index", + "units": "Index" + }, + { + "name": "inputSource", + "ctype": "uint8_t", + "desc": "Enum `inputSource_e` Input source for the mix", + "units": "Enum", + "enum": "inputSource_e" + }, + { + "name": "rate", + "ctype": "int16_t", + "desc": "Mixing rate/weight (`-1000` to `+1000`, percent with sign)", + "units": "%" + }, + { + "name": "speed", + "ctype": "uint8_t", + "desc": "Speed/Slew rate limit (`0`=instant, higher slows response)", + "units": "0-255" + }, + { + "name": "legacyMinMax", + "ctype": "uint16_t", + "desc": "Ignored" + }, + { + "name": "legacyBox", + "ctype": "uint8_t", + "desc": "Ignored" + } + ] + }, + "reply": null, + "notes": "Expects 9 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`. Superseded by `MSP2_INAV_SET_SERVO_MIXER`.", + "description": "Sets a single custom servo mixer rule (legacy format)." + }, + "MSP_SET_PASSTHROUGH": { + "code": 245, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "status", + "ctype": "uint8_t", + "desc": "1 if passthrough started successfully, 0 on error (e.g., port not found). For 4way, returns number of ESCs found", + "units": "" + } + ] + }, + "notes": "Accepts 0 bytes (defaults to ESC 4-way) or up to 2 bytes for mode/argument. If successful, sets `mspPostProcessFn` to the appropriate handler (`mspSerialPassthroughFn` or `esc4wayProcess`). This handler takes over the serial port after the reply is sent. Requires `USE_SERIAL_4WAY_BLHELI_INTERFACE` for ESC passthrough.", + "description": "Enables serial passthrough mode to peripherals like ESCs (BLHeli 4-way) or other serial devices." + }, + "MSP_RTC": { + "code": 246, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "seconds", + "ctype": "int32_t", + "desc": "Seconds since epoch (or relative time if not set). 0 if RTC time unknown", + "units": "Seconds" + }, + { + "name": "millis", + "ctype": "uint16_t", + "desc": "Millisecond part of the time. 0 if RTC time unknown", + "units": "Milliseconds" + } + ] + }, + "notes": "Requires RTC hardware/support. Returns (0, 0) if time is not available/set.", + "description": "Retrieves the current Real-Time Clock time." }, - "reply": null, - "notes": "Requires `USE_TEMPERATURE_SENSOR`. Payload must include `MAX_TEMP_SENSORS` consecutive `tempSensorConfig_t` structures (labels are uppercased).", - "description": "Sets the configuration for all onboard temperature sensors." - }, - "MSP2_INAV_TEMPERATURES": { - "code": 8222, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "temperature", - "ctype": "int16_t", - "desc": "Current temperature reading. -1000 if sensor is invalid or reading failed", - "units": "0.1Β°C" + "MSP_SET_RTC": { + "code": 247, + "mspv": 1, + "request": { + "payload": [ + { + "name": "seconds", + "ctype": "int32_t", + "desc": "Seconds component of time to set", + "units": "Seconds" + }, + { + "name": "millis", + "ctype": "uint16_t", + "desc": "Millisecond component of time to set", + "units": "Milliseconds" + } + ] + }, + "reply": null, + "notes": "Requires RTC hardware/support. Expects 6 bytes. Uses `rtcSet()`.", + "description": "Sets the Real-Time Clock time." + }, + "MSP_EEPROM_WRITE": { + "code": 250, + "mspv": 1, + "request": null, + "reply": null, + "notes": "Will fail if armed. Suspends RX, calls `writeEEPROM()`, `readEEPROM()`, resumes RX.", + "description": "Saves the current configuration from RAM to non-volatile memory (EEPROM/Flash)." + }, + "MSP_RESERVE_1": { + "code": 251, + "mspv": 1, + "request": null, + "reply": null, + "name": "MSP_RESERVE_1", + "missing": true + }, + "MSP_RESERVE_2": { + "code": 252, + "mspv": 1, + "request": null, + "reply": null, + "name": "MSP_RESERVE_2", + "missing": true + }, + "MSP_DEBUGMSG": { + "code": 253, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "Message Text", + "desc": "Debug message text (not NUL-terminated). See [serial printf debugging](https://github.com/iNavFlight/inav/blob/master/docs/development/serial_printf_debugging.md)", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Published via the LOG UART or shared MSP/LOG port using `mspSerialPushPort()`.", + "description": "Retrieves debug (\"serial printf\") messages from the firmware." + }, + "MSP_DEBUG": { + "code": 254, + "mspv": 1, + "request": null, + "reply": { + "payload": [ + { + "name": "debugValues", + "desc": "First 4 values from the `debug` array", + "ctype": "uint16_t", + "array": true, + "array_size": 4, + "units": "" + } + ] + }, + "notes": "Useful for developers. Values are truncated to the lower 16 bits of each `debug[]` entry. See `MSP2_INAV_DEBUG` for full 32-bit values.", + "description": "Retrieves values from the firmware's `debug[]` array (legacy 16-bit version)." + }, + "MSP_V2_FRAME": { + "code": 255, + "mspv": 1, + "request": null, + "reply": null, + "notes": "See MSPv2 documentation for the actual frame structure that follows this indicator.", + "description": "This ID is used as a *payload indicator* within an MSPv1 message structure (`$M>`) to signify that the following payload conforms to the MSPv2 format. It's not a command itself." + }, + "MSP2_COMMON_TZ": { + "code": 4097, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "tzOffsetMinutes", + "ctype": "int16_t", + "desc": "Time zone offset from UTC (`timeConfig()->tz_offset`)", + "units": "Minutes" + }, + { + "name": "tzAutoDst", + "ctype": "uint8_t", + "desc": "Automatic daylight saving time enabled (`timeConfig()->tz_automatic_dst`)", + "units": "Boolean" + } + ] + }, + "notes": "", + "description": "Gets the time zone offset configuration." + }, + "MSP2_COMMON_SET_TZ": { + "code": 4098, + "mspv": 2, + "request": null, + "reply": null, + "notes": "Accepts 2 or 3 bytes.", + "description": "Sets the time zone offset configuration.", + "variants": { + "dataSize == 2": { + "description": "dataSize == 2", + "request": { + "payload": [ + { + "name": "tz_offset", + "ctype": "int16_t", + "desc": "Timezone offset from UTC.", + "units": "minutes" + } + ] + }, + "reply": null + }, + "dataSize == 3": { + "description": "dataSize == 3", + "request": { + "payload": [ + { + "name": "tz_offset", + "ctype": "int16_t", + "desc": "Timezone offset from UTC.", + "units": "minutes" + }, + { + "name": "tz_automatic_dst", + "ctype": "uint8_t", + "desc": "Automatic DST enable (0/1).", + "units": "bool" + } + ] + }, + "reply": null } - ], - "repeating": "MAX_TEMP_SENSORS" + } }, - "variable_len": "MAX_TEMP_SENSORS", - "notes": "Requires `USE_TEMPERATURE_SENSOR`.", - "description": "Retrieves the current readings from all configured temperature sensors." - }, - "MSP_SIMULATOR": { - "code": 8223, - "mspv": 2, - "request": { - "payload": [ - { - "name": "simulatorVersion", - "ctype": "uint8_t", - "desc": "Version of the simulator protocol (`SIMULATOR_MSP_VERSION`)", - "units": "" - }, - { - "name": "simulatorFlags_t", - "ctype": "uint8_t", - "desc": "Bitmask: Options for HITL (`HITL_*` flags)", - "units": "Bitmask", - "bitmask": true - }, - { - "name": "gpsFixType", - "ctype": "uint8_t", - "desc": "Enum `gpsFixType_e` Type of GPS fix (If `HITL_HAS_NEW_GPS_DATA`)", - "units": "Enum", - "enum": "gpsFixType_e" - }, - { - "name": "gpsNumSat", - "ctype": "uint8_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated satellite count", - "units": "" - }, - { - "name": "gpsLat", - "ctype": "int32_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated latitude (1e7 deg)", - "units": "" - }, - { - "name": "gpsLon", - "ctype": "int32_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated longitude (1e7 deg)", - "units": "" - }, - { - "name": "gpsAlt", - "ctype": "int32_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated altitude (cm)", - "units": "" - }, - { - "name": "gpsSpeed", - "ctype": "uint16_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated ground speed (cm/s)", - "units": "" - }, - { - "name": "gpsCourse", - "ctype": "uint16_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated ground course (deci-deg)", - "units": "" - }, - { - "name": "gpsVelN", - "ctype": "int16_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated North velocity (cm/s)", - "units": "" - }, - { - "name": "gpsVelE", - "ctype": "int16_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated East velocity (cm/s)", - "units": "" - }, - { - "name": "gpsVelD", - "ctype": "int16_t", - "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated Down velocity (cm/s)", - "units": "" - }, - { - "name": "imuRoll", - "ctype": "int16_t", - "desc": "(If NOT `HITL_USE_IMU`) Simulated Roll (deci-deg)", - "units": "" - }, - { - "name": "imuPitch", - "ctype": "int16_t", - "desc": "(If NOT `HITL_USE_IMU`) Simulated Pitch (deci-deg)", - "units": "" - }, - { - "name": "imuYaw", - "ctype": "int16_t", - "desc": "(If NOT `HITL_USE_IMU`) Simulated Yaw (deci-deg)", - "units": "" - }, - { - "name": "accX", - "ctype": "int16_t", - "desc": "mG (G * 1000)", - "units": "" - }, - { - "name": "accY", - "ctype": "int16_t", - "desc": "mG (G * 1000)", - "units": "" - }, - { - "name": "accZ", - "ctype": "int16_t", - "desc": "mG (G * 1000)", - "units": "" - }, - { - "name": "gyroX", - "ctype": "int16_t", - "desc": "dps * 16", - "units": "" - }, - { - "name": "gyroY", - "ctype": "int16_t", - "desc": "dps * 16", - "units": "" - }, - { - "name": "gyroZ", - "ctype": "int16_t", - "desc": "dps * 16", - "units": "" - }, - { - "name": "baroPressure", - "ctype": "uint32_t", - "desc": "Pa", - "units": "" - }, - { - "name": "magX", - "ctype": "int16_t", - "desc": "Scaled", - "units": "" - }, - { - "name": "magY", - "ctype": "int16_t", - "desc": "Scaled", - "units": "" - }, - { - "name": "magZ", - "ctype": "int16_t", - "desc": "Scaled", - "units": "" - }, - { - "name": "vbat", - "ctype": "uint8_t", - "desc": "(If `HITL_EXT_BATTERY_VOLTAGE`) Simulated battery voltage (0.1V units)", - "units": "" - }, - { - "name": "airspeed", - "ctype": "uint16_t", - "desc": "(If `HITL_AIRSPEED`) Simulated airspeed (cm/s)", - "units": "" - }, - { - "name": "extFlags", - "ctype": "uint8_t", - "desc": "(If `HITL_EXTENDED_FLAGS`) Additional flags (upper 8 bits)", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "stabilizedRoll", - "ctype": "uint16_t", - "desc": "Stabilized Roll command output (-500 to 500)", - "units": "" - }, - { - "name": "stabilizedPitch", - "ctype": "uint16_t", - "desc": "Stabilized Pitch command output (-500 to 500)", - "units": "" - }, - { - "name": "stabilizedYaw", - "ctype": "uint16_t", - "desc": "Stabilized Yaw command output (-500 to 500)", - "units": "" - }, - { - "name": "stabilizedThrottle", - "ctype": "uint16_t", - "desc": "Stabilized Throttle command output (-500 to 500 if armed, else -500)", - "units": "" - }, - { - "name": "debugFlags", - "ctype": "uint8_t", - "desc": "Packed flags: Debug index (0-7), Platform type, Armed state, OSD feature status", - "units": "" - }, - { - "name": "debugValue", - "ctype": "uint32_t", - "desc": "Current debug value (`debug[simulatorData.debugIndex]`)", - "units": "" - }, - { - "name": "attitudeRoll", - "ctype": "int16_t", - "desc": "Current estimated Roll (deci-deg)", - "units": "" - }, - { - "name": "attitudePitch", - "ctype": "int16_t", - "desc": "Current estimated Pitch (deci-deg)", - "units": "" - }, - { - "name": "attitudeYaw", - "ctype": "int16_t", - "desc": "Current estimated Yaw (deci-deg)", - "units": "" - }, - { - "name": "osdHeader", - "ctype": "uint8_t", - "desc": "OSD RLE Header (255)", - "units": "", - "optional": true - }, - { - "name": "osdRows", - "ctype": "uint8_t", - "desc": "(If OSD supported) Number of OSD rows", - "units": "", - "optional": true - }, - { - "name": "osdCols", - "ctype": "uint8_t", - "desc": "(If OSD supported) Number of OSD columns", - "units": "", - "optional": true - }, - { - "name": "osdStartY", - "ctype": "uint8_t", - "desc": "(If OSD supported) Starting row for RLE data", - "units": "", - "optional": true - }, - { - "name": "osdStartX", - "ctype": "uint8_t", - "desc": "(If OSD supported) Starting column for RLE data", - "units": "", - "optional": true - }, - { - "name": "osdRleData", - "desc": "(If OSD supported) Run-length encoded OSD character data. Terminated by `[0, 0]`", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "", - "optional": true - } - ] + "MSP2_COMMON_SETTING": { + "code": 4099, + "mspv": 2, + "request": { + "payload": [ + { + "name": "settingIdentifier", + "ctype": "Varies", + "desc": "Setting name (null-terminated string) OR index selector (`0x00` followed by `uint16_t` index)", + "polymorph": true, + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "settingValue", + "desc": "Raw byte value of the setting. Size depends on the setting's type (`settingGetValueSize()`)", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Returns error if setting not found. Use `MSP2_COMMON_SETTING_INFO` to discover settings, types, and sizes.", + "description": "Gets the value of a specific configuration setting, identified by name or index." }, - "variable_len": true, - "notes": "Requires `USE_SIMULATOR`. Complex message handling state changes for enabling/disabling HITL. Sensor data is injected directly. OSD data is sent using a custom RLE scheme. See `simulatorData` struct and associated code for details.", - "description": "Handles Hardware-in-the-Loop (HITL) simulation data exchange. Receives simulated sensor data and options, sends back control outputs and debug info." - }, - "MSP2_INAV_SERVO_MIXER": { - "code": 8224, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "targetChannel", - "ctype": "uint8_t", - "desc": "Servo output channel index (0-based)", - "units": "" - }, - { - "name": "inputSource", - "ctype": "uint8_t", - "desc": "Enum `inputSource_e` Input source", - "units": "", - "enum": "inputSource_e" - }, - { - "name": "rate", - "ctype": "int16_t", - "desc": "Mixing rate/weight", - "units": "" - }, - { - "name": "speed", - "ctype": "uint8_t", - "desc": "Speed/Slew rate limit (0-100)", - "units": "" - }, - { - "name": "conditionId", - "ctype": "int8_t", - "desc": "Logic Condition ID (0 to `MAX_LOGIC_CONDITIONS - 1`, or 255/-1 if none/disabled)", - "units": "" - }, - { - "name": "p2TargetChannel", - "ctype": "uint8_t", - "desc": "(Optional) Profile 2 Target channel", - "units": "", - "optional": true - }, - { - "name": "p2InputSource", - "ctype": "uint8_t", - "desc": "(Optional) Profile 2 Enum `inputSource_e` Input source", - "units": "", - "optional": true, - "enum": "inputSource_e" - }, - { - "name": "p2Rate", - "ctype": "int16_t", - "desc": "(Optional) Profile 2 Rate", - "units": "", - "optional": true - }, - { - "name": "p2Speed", - "ctype": "uint8_t", - "desc": "(Optional) Profile 2 Speed", - "units": "", - "optional": true - }, - { - "name": "p2ConditionId", - "ctype": "int8_t", - "desc": "(Optional) Profile 2 Logic Condition ID", - "units": "", - "optional": true - } - ], - "repeating": "MAX_SERVO_RULES" + "MSP2_COMMON_SET_SETTING": { + "code": 4100, + "mspv": 2, + "request": { + "payload": [ + { + "name": "settingIdentifier", + "ctype": "Varies", + "desc": "Setting name (null-terminated string) OR Index (0x00 followed by `uint16_t` index)", + "polymorph": true, + "units": "" + }, + { + "name": "settingValue", + "desc": "Raw byte value to set for the setting. Size must match the setting's type", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "reply": null, + "variable_len": true, + "notes": "Performs type checking and range validation (min/max). Returns error if setting not found, value size mismatch, or value out of range. Handles different data types (`uint8`, `int16`, `float`, `string`, etc.) internally.", + "description": "Sets the value of a specific configuration setting, identified by name or index." + }, + "MSP2_COMMON_MOTOR_MIXER": { + "code": 4101, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "motorMix", + "desc": "Weights for a single motor `[throttle, roll, pitch, yaw]`, each encoded as `(mix + 2.0) * 1000` (range 0-4000)", + "ctype": "uint16_t", + "array": true, + "array_size": 4, + "units": "Scaled (0-4000)" + } + ], + "repeating": "MAX_SUPPORTED_MOTORS" + }, + "variable_len": "MAX_SUPPORTED_MOTORS", + "notes": "Scaling is `(float_weight + 2.0) * 1000`. `primaryMotorMixer()` provides the data. If multiple mixer profiles are enabled (`MAX_MIXER_PROFILE_COUNT > 1`), an additional block of mixes for the next profile follows immediately.", + "description": "Retrieves the current motor mixer configuration (throttle, roll, pitch, yaw weights) for each motor." }, - "variable_len": "MAX_SERVO_RULES", - "notes": "`conditionId` requires `USE_PROGRAMMING_FRAMEWORK`.", - "description": "Retrieves the custom servo mixer rules, including programming framework condition IDs, for primary and secondary mixer profiles. Supersedes `MSP_SERVO_MIX_RULES`." - }, - "MSP2_INAV_SET_SERVO_MIXER": { - "code": 8225, - "mspv": 2, - "request": { - "payload": [ - { - "name": "ruleIndex", - "ctype": "uint8_t", - "desc": "Index of the rule to set (0 to `MAX_SERVO_RULES - 1`)", - "units": "" - }, - { - "name": "targetChannel", - "ctype": "uint8_t", - "desc": "Servo output channel index", - "units": "" - }, - { - "name": "inputSource", - "ctype": "uint8_t", - "desc": "Enum `inputSource_e` Input source", - "units": "", - "enum": "inputSource_e" - }, - { - "name": "rate", - "ctype": "int16_t", - "desc": "Mixing rate/weight", - "units": "" - }, - { - "name": "speed", - "ctype": "uint8_t", - "desc": "Speed/Slew rate limit (0-100)", - "units": "" - }, - { - "name": "conditionId", - "ctype": "int8_t", - "desc": "Logic Condition ID (255/-1 if none). Ignored if `USE_PROGRAMMING_FRAMEWORK` is disabled", - "units": "" - } - ] + "MSP2_COMMON_SET_MOTOR_MIXER": { + "code": 4102, + "mspv": 2, + "request": { + "payload": [ + { + "name": "motorIndex", + "ctype": "uint8_t", + "desc": "Index of the motor to configure (0 to `MAX_SUPPORTED_MOTORS - 1`)", + "units": "Index" + }, + { + "name": "throttleWeight", + "ctype": "uint16_t", + "desc": "Sets throttle weight from `(value / 1000.0) - 2.0", + "units": "Scaled (0-4000)" + }, + { + "name": "rollWeight", + "ctype": "uint16_t", + "desc": "Sets roll weight from `(value / 1000.0) - 2.0", + "units": "Scaled (0-4000)" + }, + { + "name": "pitchWeight", + "ctype": "uint16_t", + "desc": "Sets pitch weight from `(value / 1000.0) - 2.0", + "units": "Scaled (0-4000)" + }, + { + "name": "yawWeight", + "ctype": "uint16_t", + "desc": "Sets yaw weight from `(value / 1000.0) - 2.0", + "units": "Scaled (0-4000)" + } + ] + }, + "reply": null, + "notes": "Expects 9 bytes. Modifies `primaryMotorMixerMutable()`. Returns error if index is invalid.", + "description": "Sets the motor mixer weights for a single motor in the primary mixer profile." + }, + "MSP2_COMMON_SETTING_INFO": { + "code": 4103, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "settingName", + "desc": "Null-terminated setting name", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + }, + { + "name": "pgn", + "ctype": "uint16_t", + "desc": "Parameter Group Number (PGN) ID", + "units": "" + }, + { + "name": "type", + "ctype": "uint8_t", + "desc": "Variable type (`VAR_UINT8`, `VAR_FLOAT`, etc.)", + "units": "" + }, + { + "name": "section", + "ctype": "uint8_t", + "desc": "Setting section (`MASTER_VALUE`, `PROFILE_VALUE`, etc.)", + "units": "" + }, + { + "name": "mode", + "ctype": "uint8_t", + "desc": "Setting mode (`MODE_NORMAL`, `MODE_LOOKUP`, etc.)", + "units": "" + }, + { + "name": "minValue", + "ctype": "int32_t", + "desc": "Minimum allowed value (as signed 32-bit)", + "units": "" + }, + { + "name": "maxValue", + "ctype": "uint32_t", + "desc": "Maximum allowed value (as unsigned 32-bit)", + "units": "" + }, + { + "name": "settingIndex", + "ctype": "uint16_t", + "desc": "Absolute index of the setting", + "units": "" + }, + { + "name": "profileIndex", + "ctype": "uint8_t", + "desc": "Current profile index (if applicable, else 0)", + "units": "" + }, + { + "name": "profileCount", + "ctype": "uint8_t", + "desc": "Total number of profiles (if applicable, else 0)", + "units": "" + }, + { + "name": "lookupNames", + "desc": "(If `mode == MODE_LOOKUP`) Series of null-terminated strings for each possible value from min to max", + "ctype": "char", + "array": true, + "array_size": 0, + "units": "" + }, + { + "name": "settingValue", + "desc": "Current raw byte value of the setting", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "", + "description": "Gets detailed information about a specific configuration setting (name, type, range, flags, current value, etc.)." }, - "reply": null, - "notes": "Expects 7 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`.", - "description": "Sets a single custom servo mixer rule, including programming framework condition ID. Supersedes `MSP_SET_SERVO_MIX_RULE`." - }, - "MSP2_INAV_LOGIC_CONDITIONS": { - "code": 8226, - "mspv": 2, - "not_implemented": true, - "request": null, - "reply": { - "payload": [ - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 if the condition is enabled", - "units": "" - }, - { - "name": "activatorId", - "ctype": "int8_t", - "desc": "Activator condition ID (-1/255 if none)", - "units": "" - }, - { - "name": "operation", - "ctype": "uint8_t", - "desc": "Enum `logicOperation_e` Logical operation (AND, OR, XOR, etc.)", - "units": "", - "enum": "logicOperation_e" - }, - { - "name": "operandAType", - "ctype": "uint8_t", - "desc": "Enum `logicOperandType_e` Type of the first operand (Flight Mode, GVAR, etc.)", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "operandAValue", - "ctype": "int32_t", - "desc": "Value/ID of the first operand", - "units": "" - }, - { - "name": "operandBType", - "ctype": "uint8_t", - "desc": "Enum `logicOperandType_e`: Type of the second operand", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "operandBValue", - "ctype": "int32_t", - "desc": "Value/ID of the second operand", - "units": "" - }, - { - "name": "flags", - "ctype": "uint8_t", - "desc": "Bitmask: Condition flags (`logicConditionFlags_e`)", - "units": "Bitmask", - "bitmask": true - } - ], - "repeating": "MAX_LOGIC_CONDITIONS" + "MSP2_COMMON_PG_LIST": { + "code": 4104, + "mspv": 2, + "request": { + "payload": [ + { + "name": "pgn", + "ctype": "uint16_t", + "desc": "(Optional) PGN ID to query. If omitted, returns all used PGNs", + "units": "", + "optional": true + } + ] + }, + "reply": { + "payload": [ + { + "name": "pgn", + "ctype": "uint16_t", + "desc": "Parameter Group Number (PGN) ID", + "units": "" + }, + { + "name": "startIndex", + "ctype": "uint16_t", + "desc": "Absolute index of the first setting in this group", + "units": "" + }, + { + "name": "endIndex", + "ctype": "uint16_t", + "desc": "Absolute index of the last setting in this group", + "units": "" + } + ], + "repeating": "for each PGN found" + }, + "variable_len": "for each PGN found", + "notes": "Allows efficient fetching of related settings by group.", + "description": "Gets a list of Parameter Group Numbers (PGNs) used by settings, along with the start and end setting indexes for each group. Can request info for a single PGN." + }, + "MSP2_COMMON_SERIAL_CONFIG": { + "code": 4105, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "identifier", + "ctype": "uint8_t", + "desc": "Port identifier Enum (`serialPortIdentifier_e`)", + "units": "", + "enum": "serialPortIdentifier_e" + }, + { + "name": "functionMask", + "ctype": "uint32_t", + "desc": "Bitmask: enabled functions (`FUNCTION_*`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "mspBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for MSP function", + "units": "" + }, + { + "name": "gpsBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for GPS function", + "units": "" + }, + { + "name": "telemetryBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for Telemetry function", + "units": "" + }, + { + "name": "peripheralBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for other peripheral functions", + "units": "" + } + ], + "repeating": "for each available serial port" + }, + "variable_len": "for each available serial port", + "notes": "Baud rate indexes map to actual baud rates (e.g., 9600, 115200). See `baudRates` array.", + "description": "Retrieves the configuration for all available serial ports." }, - "variable_len": "MAX_LOGIC_CONDITIONS", - "notes": "Deprecated, causes buffer overflow for 14*64 bytes", - "description": "Retrieves the configuration of all defined Logic Conditions. Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure." - }, - "MSP2_INAV_SET_LOGIC_CONDITIONS": { - "code": 8227, - "mspv": 2, - "request": { - "payload": [ - { - "name": "conditionIndex", - "ctype": "uint8_t", - "desc": "Index of the condition to set (0 to `MAX_LOGIC_CONDITIONS - 1`)", - "units": "" - }, - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 to enable the condition", - "units": "" - }, - { - "name": "activatorId", - "ctype": "int8_t", - "desc": "Activator condition ID (-1/255 if none)", - "units": "" - }, - { - "name": "operation", - "ctype": "uint8_t", - "desc": "Enum `logicOperation_e` Logical operation", - "units": "", - "enum": "logicOperation_e" - }, - { - "name": "operandAType", - "ctype": "uint8_t", - "desc": "Enum `logicOperandType_e` Type of operand A", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "operandAValue", - "ctype": "int32_t", - "desc": "Value/ID of operand A", - "units": "" - }, - { - "name": "operandBType", - "ctype": "uint8_t", - "desc": "Enum `logicOperandType_e` Type of operand B", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "operandBValue", - "ctype": "int32_t", - "desc": "Value/ID of operand B", - "units": "" - }, - { - "name": "flags", - "ctype": "uint8_t", - "desc": "Bitmask: Condition flags (`logicConditionFlags_e`)", - "units": "Bitmask", - "bitmask": true - } - ] + "MSP2_COMMON_SET_SERIAL_CONFIG": { + "code": 4106, + "mspv": 2, + "request": { + "payload": [ + { + "name": "identifier", + "ctype": "uint8_t", + "desc": "Port identifier Enum (`serialPortIdentifier_e`)", + "units": "", + "enum": "serialPortIdentifier_e" + }, + { + "name": "functionMask", + "ctype": "uint32_t", + "desc": "Bitmask: functions to enable", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "mspBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for MSP", + "units": "" + }, + { + "name": "gpsBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for GPS", + "units": "" + }, + { + "name": "telemetryBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for Telemetry", + "units": "" + }, + { + "name": "peripheralBaudIndex", + "ctype": "uint8_t", + "desc": "Baud rate index for peripherals", + "units": "" + } + ], + "repeating": "for each port being configured" + }, + "reply": null, + "variable_len": "for each port being configured", + "notes": "Payload size must be a multiple of the size of one port config entry (1 + 4 + 4 = 9 bytes). Returns error if identifier is invalid or size is incorrect. Baud rate indexes are constrained `BAUD_MIN` to `BAUD_MAX`.", + "description": "Sets the configuration for one or more serial ports." + }, + "MSP2_COMMON_SET_RADAR_POS": { + "code": 4107, + "mspv": 2, + "request": { + "payload": [ + { + "name": "poiIndex", + "ctype": "uint8_t", + "desc": "Index of the POI slot (0 to `RADAR_MAX_POIS - 1`)", + "units": "Index" + }, + { + "name": "state", + "ctype": "uint8_t", + "desc": "Status of the POI (0=undefined, 1=armed, 2=lost)", + "units": "" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude of the POI", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude of the POI", + "units": "deg * 1e7" + }, + { + "name": "altitude", + "ctype": "int32_t", + "desc": "Altitude of the POI", + "units": "cm" + }, + { + "name": "heading", + "ctype": "uint16_t", + "desc": "Heading of the POI", + "units": "degrees" + }, + { + "name": "speed", + "ctype": "uint16_t", + "desc": "Speed of the POI", + "units": "cm/s" + }, + { + "name": "linkQuality", + "ctype": "uint8_t", + "desc": "Link quality indicator", + "units": "0-4" + } + ] + }, + "reply": null, + "notes": "Expects 19 bytes. POI index is clamped to `RADAR_MAX_POIS - 1`. Updates the `radar_pois` array.", + "description": "Sets the position and status information for a \"radar\" Point of Interest (POI). Used for displaying other craft/objects on the OSD map." + }, + "MSP2_COMMON_SET_RADAR_ITD": { + "code": 4108, + "mspv": 2, + "request": null, + "reply": null, + "not_implemented": true, + "notes": "Not implemented in INAV `fc_msp.c`.", + "description": "Sets radar information to display (likely internal/unused)." + }, + "MSP2_COMMON_SET_MSP_RC_LINK_STATS": { + "code": 4109, + "mspv": 2, + "request": { + "payload": [ + { + "name": "sublinkID", + "ctype": "uint8_t", + "desc": "Sublink identifier (usually 0)" + }, + { + "name": "validLink", + "ctype": "uint8_t", + "desc": "Indicates if the link is currently valid (not in failsafe)", + "units": "Boolean" + }, + { + "name": "rssiPercent", + "ctype": "uint8_t", + "desc": "Uplink RSSI percentage (0-100)", + "units": "%" + }, + { + "name": "uplinkRSSI_dBm", + "ctype": "uint8_t", + "desc": "Uplink RSSI in dBm (sent as positive, e.g., 70 means -70dBm)", + "units": "-dBm" + }, + { + "name": "downlinkLQ", + "ctype": "uint8_t", + "desc": "Downlink Link Quality (0-100)", + "units": "%" + }, + { + "name": "uplinkLQ", + "ctype": "uint8_t", + "desc": "Uplink Link Quality (0-100)", + "units": "%" + }, + { + "name": "uplinkSNR", + "ctype": "int8_t", + "desc": "Uplink Signal-to-Noise Ratio", + "units": "dB" + } + ] + }, + "reply": null, + "notes": "Requires `USE_RX_MSP`. Expects at least 7 bytes. Updates `rxLinkStatistics` and sets RSSI via `setRSSIFromMSP_RC()` only if `sublinkID` is 0. This message expects **no reply** (`MSP_RESULT_NO_REPLY`).", + "description": "Provides RC link statistics (RSSI, LQ) to the FC, typically from an MSP-based RC link (like ExpressLRS). Sent periodically by the RC link." }, - "reply": null, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 15 bytes. Returns error if index is invalid.", - "description": "Sets the configuration for a single Logic Condition by its index." - }, - "MSP2_INAV_GLOBAL_FUNCTIONS": { - "code": 8228, - "mspv": 2, - "not_implemented": true - }, - "MSP2_INAV_SET_GLOBAL_FUNCTIONS": { - "code": 8229, - "mspv": 2, - "not_implemented": true - }, - "MSP2_INAV_LOGIC_CONDITIONS_STATUS": { - "code": 8230, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "conditionValues", - "ctype": "int32_t", - "desc": "Array of current values for each logic condition (`logicConditionGetValue(i)`). 1 for true, 0 for false, or numerical value depending on operation", - "array": true, - "array_size": 64, - "array_size_define": "MAX_LOGIC_CONDITIONS", - "units": "" - } - ] + "MSP2_COMMON_SET_MSP_RC_INFO": { + "code": 4110, + "mspv": 2, + "request": { + "payload": [ + { + "name": "sublinkID", + "ctype": "uint8_t", + "desc": "Sublink identifier (usually 0)" + }, + { + "name": "uplinkTxPower", + "ctype": "uint16_t", + "desc": "Uplink transmitter power level", + "units": "mW" + }, + { + "name": "downlinkTxPower", + "ctype": "uint16_t", + "desc": "Downlink transmitter power level", + "units": "mW" + }, + { + "name": "band", + "ctype": "char", + "desc": "Operating band string (e.g., \"2G4\", \"900\"), null-terminated/padded", + "array": true, + "array_size": 4 + }, + { + "name": "mode", + "ctype": "char", + "desc": "Operating mode/rate string (e.g., \"100HZ\", \"F1000\"), null-terminated/padded", + "array": true, + "array_size": 6 + } + ] + }, + "reply": null, + "notes": "Requires `USE_RX_MSP`. Expects at least 15 bytes. Updates `rxLinkStatistics` only if `sublinkID` is 0. Converts band/mode strings to uppercase. This message expects **no reply** (`MSP_RESULT_NO_REPLY`).", + "description": "Provides additional RC link information (power levels, band, mode) to the FC from an MSP-based RC link. Sent less frequently than link stats." + }, + "MSP2_COMMON_GET_RADAR_GPS": { + "code": 4111, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "poiLatitude", + "ctype": "int32_t", + "desc": "Latitude of a radar POI", + "units": "deg * 1e7" + }, + { + "name": "poiLongitude", + "ctype": "int32_t", + "desc": "Longitude of a radar POI", + "units": "deg * 1e7" + }, + { + "name": "poiAltitude", + "ctype": "int32_t", + "desc": "Altitude of a radar POI", + "units": "cm" + } + ], + "repeating": "RADAR_MAX_POIS" + }, + "notes": "Returns the stored GPS coordinates for all radar POIs (`radar_pois[i].gps`).", + "description": "Provides the GPS positions (latitude, longitude, altitude) for each radar point of interest." }, - "variable_len": true, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", - "description": "Retrieves the current evaluated status (true/false or numerical value) of all logic conditions." - }, - "MSP2_INAV_GVAR_STATUS": { - "code": 8231, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "gvarValues", - "desc": "Array of current values for each global variable (`gvGet(i)`)", - "ctype": "int32_t", - "array": true, - "array_size": 8, - "array_size_define": "MAX_GLOBAL_VARIABLES", - "units": "" - } - ] + "MSP2_SENSOR_RANGEFINDER": { + "code": 7937, + "mspv": 2, + "request": { + "payload": [ + { + "name": "quality", + "ctype": "uint8_t", + "desc": "Quality of the measurement", + "units": "0-255" + }, + { + "name": "distanceMm", + "ctype": "int32_t", + "desc": "Measured distance. Negative value indicates out of range", + "units": "mm" + } + ] + }, + "reply": null, + "notes": "Requires `USE_RANGEFINDER_MSP`. Calls `mspRangefinderReceiveNewData()`.", + "description": "Provides rangefinder data (distance, quality) from an external MSP-based sensor." }, - "variable_len": true, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", - "description": "Retrieves the current values of all Global Variables (GVARS)." - }, - "MSP2_INAV_PROGRAMMING_PID": { - "code": 8232, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 if the PID is enabled", - "units": "" - }, - { - "name": "setpointType", - "ctype": "uint8_t", - "desc": "Enum (`logicOperandType_e`) Type of the setpoint source", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "setpointValue", - "ctype": "int32_t", - "desc": "Value/ID of the setpoint source", - "units": "" - }, - { - "name": "measurementType", - "ctype": "uint8_t", - "desc": "Enum (`logicOperandType_e`) Type of the measurement source", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "measurementValue", - "ctype": "int32_t", - "desc": "Value/ID of the measurement source", - "units": "" - }, - { - "name": "gainP", - "ctype": "uint16_t", - "desc": "Proportional gain", - "units": "" - }, - { - "name": "gainI", - "ctype": "uint16_t", - "desc": "Integral gain", - "units": "" - }, - { - "name": "gainD", - "ctype": "uint16_t", - "desc": "Derivative gain", - "units": "" - }, - { - "name": "gainFF", - "ctype": "uint16_t", - "desc": "Feed-forward gain", - "units": "" - } - ], - "repeating": "MAX_PROGRAMMING_PID_COUNT" + "MSP2_SENSOR_OPTIC_FLOW": { + "code": 7938, + "mspv": 2, + "request": { + "payload": [ + { + "name": "quality", + "ctype": "uint8_t", + "desc": "Quality of the measurement (0-255)", + "units": "" + }, + { + "name": "motionX", + "ctype": "int32_t", + "desc": "Raw integrated flow value X", + "units": "" + }, + { + "name": "motionY", + "ctype": "int32_t", + "desc": "Raw integrated flow value Y", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_OPFLOW_MSP`. Calls `mspOpflowReceiveNewData()`.", + "description": "Provides optical flow data (motion, quality) from an external MSP-based sensor." }, - "variable_len": "MAX_PROGRAMMING_PID_COUNT", - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. See `programmingPid_t` structure.", - "description": "Retrieves the configuration of all Programming PIDs." - }, - "MSP2_INAV_SET_PROGRAMMING_PID": { - "code": 8233, - "mspv": 2, - "request": { - "payload": [ - { - "name": "pidIndex", - "ctype": "uint8_t", - "desc": "Index of the Programming PID to set (0 to `MAX_PROGRAMMING_PID_COUNT - 1`)", - "units": "" - }, - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 to enable the PID", - "units": "" - }, - { - "name": "setpointType", - "ctype": "uint8_t", - "desc": "Enum (`logicOperandType_e`) Type of the setpoint source", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "setpointValue", - "ctype": "int32_t", - "desc": "Value/ID of the setpoint source", - "units": "" - }, - { - "name": "measurementType", - "ctype": "uint8_t", - "desc": "Enum (`logicOperandType_e`) Type of the measurement source", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "measurementValue", - "ctype": "int32_t", - "desc": "Value/ID of the measurement source", - "units": "" - }, - { - "name": "gainP", - "ctype": "uint16_t", - "desc": "Proportional gain", - "units": "" - }, - { - "name": "gainI", - "ctype": "uint16_t", - "desc": "Integral gain", - "units": "" - }, - { - "name": "gainD", - "ctype": "uint16_t", - "desc": "Derivative gain", - "units": "" - }, - { - "name": "gainFF", - "ctype": "uint16_t", - "desc": "Feed-forward gain", - "units": "" - } - ] + "MSP2_SENSOR_GPS": { + "code": 7939, + "mspv": 2, + "request": { + "payload": [ + { + "name": "instance", + "ctype": "uint8_t", + "desc": "Sensor instance number (for multi-GPS)" + }, + { + "name": "gpsWeek", + "ctype": "uint16_t", + "desc": "GPS week number (0xFFFF if unavailable)" + }, + { + "name": "msTOW", + "ctype": "uint32_t", + "desc": "Milliseconds Time of Week", + "units": "ms" + }, + { + "name": "fixType", + "ctype": "uint8_t", + "desc": "Enum `gpsFixType_e` Type of GPS fix", + "units": "Enum", + "enum": "gpsFixType_e" + }, + { + "name": "satellitesInView", + "ctype": "uint8_t", + "desc": "Number of satellites used in solution", + "units": "Count" + }, + { + "name": "hPosAccuracy", + "ctype": "uint16_t", + "desc": "Horizontal position accuracy estimate in milimeters", + "units": "mm" + }, + { + "name": "vPosAccuracy", + "ctype": "uint16_t", + "desc": "Vertical position accuracy estimate in milimeters", + "units": "mm" + }, + { + "name": "hVelAccuracy", + "ctype": "uint16_t", + "desc": "Horizontal velocity accuracy estimate", + "units": "cm/s" + }, + { + "name": "hdop", + "ctype": "uint16_t", + "desc": "Horizontal Dilution of Precision", + "units": "HDOP * 100" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude", + "units": "deg * 1e7" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude", + "units": "deg * 1e7" + }, + { + "name": "mslAltitude", + "ctype": "int32_t", + "desc": "Altitude above Mean Sea Level", + "units": "cm" + }, + { + "name": "nedVelNorth", + "ctype": "int32_t", + "desc": "North velocity (NED frame)", + "units": "cm/s" + }, + { + "name": "nedVelEast", + "ctype": "int32_t", + "desc": "East velocity (NED frame)", + "units": "cm/s" + }, + { + "name": "nedVelDown", + "ctype": "int32_t", + "desc": "Down velocity (NED frame)", + "units": "cm/s" + }, + { + "name": "groundCourse", + "ctype": "uint16_t", + "desc": "Ground course (0-36000)", + "units": "deg * 100" + }, + { + "name": "trueYaw", + "ctype": "uint16_t", + "desc": "True heading/yaw (0-36000, 65535 if unavailable)", + "units": "deg * 100" + }, + { + "name": "year", + "ctype": "uint16_t", + "desc": "Year (e.g., 2023)" + }, + { + "name": "month", + "ctype": "uint8_t", + "desc": "Month (1-12)" + }, + { + "name": "day", + "ctype": "uint8_t", + "desc": "Day of month (1-31)" + }, + { + "name": "hour", + "ctype": "uint8_t", + "desc": "Hour (0-23)" + }, + { + "name": "min", + "ctype": "uint8_t", + "desc": "Minute (0-59)" + }, + { + "name": "sec", + "ctype": "uint8_t", + "desc": "Second (0-59)" + } + ] + }, + "reply": null, + "notes": "Requires `USE_GPS_PROTO_MSP`. Calls `mspGPSReceiveNewData()`.", + "description": "Provides detailed GPS data from an external MSP-based GPS module." }, - "reply": null, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 20 bytes. Returns error if index is invalid.", - "description": "Sets the configuration for a single Programming PID by its index." - }, - "MSP2_INAV_PROGRAMMING_PID_STATUS": { - "code": 8234, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "pidOutputs", - "desc": "Array of current output values for each Programming PID (`programmingPidGetOutput(i)`, signed)", - "array": true, - "ctype": "int32_t", - "array_size": 4, - "array_size_define": "MAX_PROGRAMMING_PID_COUNT", - "units": "" - } - ] + "MSP2_SENSOR_COMPASS": { + "code": 7940, + "mspv": 2, + "request": { + "payload": [ + { + "name": "instance", + "ctype": "uint8_t", + "desc": "Sensor instance number" + }, + { + "name": "timeMs", + "ctype": "uint32_t", + "desc": "Timestamp from the sensor", + "units": "ms" + }, + { + "name": "magX", + "ctype": "int16_t", + "desc": "Front component reading", + "units": "mGauss" + }, + { + "name": "magY", + "ctype": "int16_t", + "desc": "Right component reading", + "units": "mGauss" + }, + { + "name": "magZ", + "ctype": "int16_t", + "desc": "Down component reading", + "units": "mGauss" + } + ] + }, + "reply": null, + "notes": "Requires `USE_MAG_MSP`. Calls `mspMagReceiveNewData()`.", + "description": "Provides magnetometer data from an external MSP-based compass module." }, - "variable_len": true, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", - "description": "Retrieves the current output value of all Programming PIDs." - }, - "MSP2_PID": { - "code": 8240, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "P", - "ctype": "uint8_t", - "desc": "Proportional gain (`pidBank()->pid[i].P`), constrained 0-255", - "units": "" - }, - { - "name": "I", - "ctype": "uint8_t", - "desc": "Integral gain (`pidBank()->pid[i].I`), constrained 0-255", - "units": "" - }, - { - "name": "D", - "ctype": "uint8_t", - "desc": "Derivative gain (`pidBank()->pid[i].D`), constrained 0-255", - "units": "" - }, - { - "name": "FF", - "ctype": "uint8_t", - "desc": "Feed-forward gain (`pidBank()->pid[i].FF`), constrained 0-255", - "units": "" - } - ], - "repeating": "PID_ITEM_COUNT" + "MSP2_SENSOR_BAROMETER": { + "code": 7941, + "mspv": 2, + "request": { + "payload": [ + { + "name": "instance", + "ctype": "uint8_t", + "desc": "Sensor instance number" + }, + { + "name": "timeMs", + "ctype": "uint32_t", + "desc": "Timestamp from the sensor", + "units": "ms" + }, + { + "name": "pressurePa", + "ctype": "float", + "desc": "Absolute pressure", + "units": "Pa" + }, + { + "name": "temp", + "ctype": "int16_t", + "desc": "Temperature", + "units": "0.01 deg C" + } + ] + }, + "reply": null, + "notes": "Requires `USE_BARO_MSP`. Calls `mspBaroReceiveNewData()`.", + "description": "Provides barometer data from an external MSP-based barometer module." }, - "variable_len": "PID_ITEM_COUNT", - "notes": "`PID_ITEM_COUNT` defines the number of standard PID controllers (Roll, Pitch, Yaw, Alt, Vel, etc.). Updates from EZ-Tune if enabled.", - "description": "Retrieves the standard PID controller gains (P, I, D, FF) for the current PID profile." - }, - "MSP2_SET_PID": { - "code": 8241, - "mspv": 2, - "request": { - "payload": [ - { - "name": "P", - "ctype": "uint8_t", - "desc": "Sets Proportional gain (`pidBankMutable()->pid[i].P`)", - "units": "" - }, - { - "name": "I", - "ctype": "uint8_t", - "desc": "Sets Integral gain (`pidBankMutable()->pid[i].I`)", - "units": "" - }, - { - "name": "D", - "ctype": "uint8_t", - "desc": "Sets Derivative gain (`pidBankMutable()->pid[i].D`)", - "units": "" - }, - { - "name": "FF", - "ctype": "uint8_t", - "desc": "Sets Feed-forward gain (`pidBankMutable()->pid[i].FF`)", - "units": "" - } - ], - "repeating": "PID_ITEM_COUNT" + "MSP2_SENSOR_AIRSPEED": { + "code": 7942, + "mspv": 2, + "request": { + "payload": [ + { + "name": "instance", + "ctype": "uint8_t", + "desc": "Sensor instance number" + }, + { + "name": "timeMs", + "ctype": "uint32_t", + "desc": "Timestamp from the sensor", + "units": "ms" + }, + { + "name": "diffPressurePa", + "ctype": "float", + "desc": "Differential pressure", + "units": "Pa" + }, + { + "name": "temp", + "ctype": "int16_t", + "desc": "Temperature", + "units": "0.01 deg C" + } + ] + }, + "reply": null, + "notes": "Requires `USE_PITOT_MSP`. Calls `mspPitotmeterReceiveNewData()`.", + "description": "Provides airspeed data from an external MSP-based pitot sensor module." }, - "reply": null, - "variable_len": "PID_ITEM_COUNT", - "notes": "Expects `PID_ITEM_COUNT * 4` bytes. Calls `schedulePidGainsUpdate()` and `navigationUsePIDs()`.", - "description": "Sets the standard PID controller gains (P, I, D, FF) for the current PID profile." - }, - "MSP2_INAV_OPFLOW_CALIBRATION": { - "code": 8242, - "mspv": 2, - "request": null, - "reply": null, - "notes": "Requires `USE_OPFLOW`. Will fail if armed. Calls `opflowStartCalibration()`.", - "description": "Starts the optical flow sensor calibration procedure." - }, - "MSP2_INAV_FWUPDT_PREPARE": { - "code": 8243, - "mspv": 2, - "request": { - "payload": [ - { - "name": "firmwareSize", - "ctype": "uint32_t", - "desc": "Total size of the incoming firmware file in bytes", - "units": "" - } - ] + "MSP2_SENSOR_HEADTRACKER": { + "code": 7943, + "mspv": 2, + "request": { + "payload": [ + { + "name": "...", + "ctype": "Varies", + "desc": "", + "polymorph": true, + "units": "Head tracker angles (e.g., int16 Roll, Pitch, Yaw in deci-degrees)" + } + ] + }, + "reply": null, + "variable_len": true, + "notes": "Requires `USE_HEADTRACKER` and `USE_HEADTRACKER_MSP`. Calls `mspHeadTrackerReceiverNewData()`. Payload structure needs verification from `mspHeadTrackerReceiverNewData` implementation.", + "description": "Provides head tracker orientation data." + }, + "MSP2_INAV_STATUS": { + "code": 8192, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "cycleTime", + "ctype": "uint16_t", + "desc": "Main loop cycle time", + "units": "Β΅s" + }, + { + "name": "i2cErrors", + "ctype": "uint16_t", + "desc": "I2C errors", + "units": "Count" + }, + { + "name": "sensorStatus", + "ctype": "uint16_t", + "desc": "Bitmask: Sensor status", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "cpuLoad", + "ctype": "uint16_t", + "desc": "Average system load percentage", + "units": "%" + }, + { + "name": "profileAndBattProfile", + "ctype": "uint8_t", + "desc": "Bits 0-3: Config profile index (`getConfigProfile()`), Bits 4-7: Battery profile index (`getConfigBatteryProfile()`)", + "units": "Packed" + }, + { + "name": "armingFlags", + "ctype": "uint32_t", + "desc": "Bitmask: Full 32-bit flight controller arming flags (`armingFlags`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "activeModes", + "ctype": "boxBitmask_t", + "desc": "Bitmask words for active flight modes (`packBoxModeFlags()`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "mixerProfile", + "ctype": "uint8_t", + "desc": "Current mixer profile index (`getConfigMixerProfile()`)", + "units": "Index" + } + ] + }, + "notes": "`sensorStatus` bits follow `packSensorStatus()` (bit 15 indicates hardware failure). `profileAndBattProfile` packs the current config profile in the low nibble and the battery profile in the high nibble. `activeModes` is emitted as a little-endian array of 32-bit words sized to `CHECKBOX_ITEM_COUNT`.", + "description": "Provides comprehensive flight controller status, extending `MSP_STATUS_EX` with full arming flags, battery profile, and mixer profile." + }, + "MSP2_INAV_OPTICAL_FLOW": { + "code": 8193, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "quality", + "ctype": "uint8_t", + "desc": "Raw quality indicator from the sensor (`opflow.rawQuality`). 0 if `USE_OPFLOW` disabled", + "units": "0-255" + }, + { + "name": "flowRateX", + "ctype": "int16_t", + "desc": "Optical flow rate X (roll axis) (`RADIANS_TO_DEGREES(opflow.flowRate[X])`). 0 if `USE_OPFLOW` disabled", + "units": "degrees/s" + }, + { + "name": "flowRateY", + "ctype": "int16_t", + "desc": "Optical flow rate Y (pitch axis) (`RADIANS_TO_DEGREES(opflow.flowRate[Y])`). 0 if `USE_OPFLOW` disabled", + "units": "degrees/s" + }, + { + "name": "bodyRateX", + "ctype": "int16_t", + "desc": "Compensated body rate X (roll axis) (`RADIANS_TO_DEGREES(opflow.bodyRate[X])`). 0 if `USE_OPFLOW` disabled", + "units": "degrees/s" + }, + { + "name": "bodyRateY", + "ctype": "int16_t", + "desc": "Compensated body rate Y (pitch axis) (`RADIANS_TO_DEGREES(opflow.bodyRate[Y])`). 0 if `USE_OPFLOW` disabled", + "units": "degrees/s" + } + ] + }, + "notes": "Requires `USE_OPFLOW`.", + "description": "Provides data from the optical flow sensor." + }, + "MSP2_INAV_ANALOG": { + "code": 8194, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "batteryFlags", + "ctype": "uint8_t", + "desc": "Bitmask: Bit0=Full on plug-in, Bit1=Use capacity thresholds, Bits2-3=`batteryState_e` (`getBatteryState()`), Bits4-7=Cell count (`getBatteryCellCount()`)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "vbat", + "ctype": "uint16_t", + "desc": "Battery voltage (`getBatteryVoltage()`)", + "units": "0.01V" + }, + { + "name": "amperage", + "ctype": "int16_t", + "desc": "Current draw (`getAmperage()`)", + "units": "0.01A" + }, + { + "name": "powerDraw", + "ctype": "uint32_t", + "desc": "Power draw (`getPower()`)", + "units": "0.01W" + }, + { + "name": "mAhDrawn", + "ctype": "uint32_t", + "desc": "Consumed capacity (`getMAhDrawn()`)", + "units": "mAh" + }, + { + "name": "mWhDrawn", + "ctype": "uint32_t", + "desc": "Consumed energy (`getMWhDrawn()`)", + "units": "mWh" + }, + { + "name": "remainingCapacity", + "ctype": "uint32_t", + "desc": "Estimated remaining capacity (`getBatteryRemainingCapacity()`)", + "units": "Capacity unit (`batteryMetersConfig()->capacity_unit`)" + }, + { + "name": "percentageRemaining", + "ctype": "uint8_t", + "desc": "Estimated remaining capacity percentage (`calculateBatteryPercentage()`)", + "units": "%" + }, + { + "name": "rssi", + "ctype": "uint16_t", + "desc": "RSSI value (`getRSSI()`)", + "units": "Raw (0-1023)" + } + ] + }, + "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_MISC": { + "code": 8195, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "midRc", + "ctype": "uint16_t", + "desc": "Mid RC value (`PWM_RANGE_MIDDLE`)", + "units": "PWM" + }, + { + "name": "legacyMinThrottle", + "ctype": "uint16_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "maxThrottle", + "ctype": "uint16_t", + "desc": "Maximum throttle command (`getMaxThrottle()`)", + "units": "PWM" + }, + { + "name": "minCommand", + "ctype": "uint16_t", + "desc": "Minimum motor command (`motorConfig()->mincommand`)", + "units": "PWM" + }, + { + "name": "failsafeThrottle", + "ctype": "uint16_t", + "desc": "Failsafe throttle level (`currentBatteryProfile->failsafe_throttle`)", + "units": "PWM" + }, + { + "name": "gpsType", + "ctype": "uint8_t", + "desc": "Enum `gpsProvider_e` GPS provider type (`gpsConfig()->provider`). 0 if `USE_GPS` disabled", + "units": "Enum", + "enum": "gpsProvider_e" + }, + { + "name": "legacyGpsBaud", + "ctype": "uint8_t", + "desc": "Always 0 (Legacy)", + "value": 0 + }, + { + "name": "gpsSbasMode", + "ctype": "uint8_t", + "desc": "Enum `sbasMode_e` GPS SBAS mode (`gpsConfig()->sbasMode`). 0 if `USE_GPS` disabled", + "units": "Enum", + "enum": "sbasMode_e" + }, + { + "name": "rssiChannel", + "ctype": "uint8_t", + "desc": "RSSI channel index (1-based, 0 disables) (`rxConfig()->rssi_channel`)", + "units": "Index" + }, + { + "name": "magDeclination", + "ctype": "int16_t", + "desc": "Magnetic declination / 10 (`compassConfig()->mag_declination / 10`). 0 if `USE_MAG` disabled", + "units": "0.1 degrees" + }, + { + "name": "vbatScale", + "ctype": "uint16_t", + "desc": "Voltage scale (`batteryMetersConfig()->voltage.scale`). 0 if `USE_ADC` disabled", + "units": "Scale" + }, + { + "name": "vbatSource", + "ctype": "uint8_t", + "desc": "Enum `batVoltageSource_e` Voltage source (`batteryMetersConfig()->voltageSource`). 0 if `USE_ADC` disabled", + "units": "Enum", + "enum": "batVoltageSource_e" + }, + { + "name": "cellCount", + "ctype": "uint8_t", + "desc": "Configured cell count (`currentBatteryProfile->cells`). 0 if `USE_ADC` disabled", + "units": "Count" + }, + { + "name": "vbatCellDetect", + "ctype": "uint16_t", + "desc": "Cell detection voltage (`currentBatteryProfile->voltage.cellDetect`). 0 if `USE_ADC` disabled", + "units": "0.01V" + }, + { + "name": "vbatMinCell", + "ctype": "uint16_t", + "desc": "Min cell voltage (`currentBatteryProfile->voltage.cellMin`). 0 if `USE_ADC` disabled", + "units": "0.01V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint16_t", + "desc": "Max cell voltage (`currentBatteryProfile->voltage.cellMax`). 0 if `USE_ADC` disabled", + "units": "0.01V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint16_t", + "desc": "Warning cell voltage (`currentBatteryProfile->voltage.cellWarning`). 0 if `USE_ADC` disabled", + "units": "0.01V" + }, + { + "name": "capacityValue", + "ctype": "uint32_t", + "desc": "Battery capacity (`currentBatteryProfile->capacity.value`)", + "units": "mAh/mWh" + }, + { + "name": "capacityWarning", + "ctype": "uint32_t", + "desc": "Capacity warning threshold (`currentBatteryProfile->capacity.warning`)", + "units": "mAh/mWh" + }, + { + "name": "capacityCritical", + "ctype": "uint32_t", + "desc": "Capacity critical threshold (`currentBatteryProfile->capacity.critical`)", + "units": "mAh/mWh" + }, + { + "name": "capacityUnit", + "ctype": "uint8_t", + "desc": "Enum `batCapacityUnit_e` Capacity unit (`batteryMetersConfig()->capacity_unit`)", + "units": "Enum", + "enum": "batCapacityUnit_e" + } + ] + }, + "notes": "", + "description": "Retrieves miscellaneous configuration settings, superseding `MSP_MISC` with higher precision and capacity fields." }, - "reply": null, - "notes": "Requires `MSP_FIRMWARE_UPDATE`. Expects 4 bytes. Returns error if preparation fails (e.g., no storage, invalid size). Calls `firmwareUpdatePrepare()`.", - "description": "Prepares the flight controller to receive a firmware update via MSP." - }, - "MSP2_INAV_FWUPDT_STORE": { - "code": 8244, - "mspv": 2, - "request": { - "payload": [ - { - "name": "firmwareChunk", - "desc": "Chunk of firmware data", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] + "MSP2_INAV_SET_MISC": { + "code": 8196, + "mspv": 2, + "request": { + "payload": [ + { + "name": "midRc", + "ctype": "uint16_t", + "desc": "Ignored", + "units": "PWM" + }, + { + "name": "legacyMinThrottle", + "ctype": "uint16_t", + "desc": "Ignored" + }, + { + "name": "legacyMaxThrottle", + "ctype": "uint16_t", + "desc": "Ignored" + }, + { + "name": "minCommand", + "ctype": "uint16_t", + "desc": "Sets `motorConfigMutable()->mincommand` (constrained)", + "units": "PWM" + }, + { + "name": "failsafeThrottle", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->failsafe_throttle` (constrained)", + "units": "PWM" + }, + { + "name": "gpsType", + "ctype": "uint8_t", + "desc": "Enum `gpsProvider_e` Sets `gpsConfigMutable()->provider` (if `USE_GPS`)", + "units": "Enum", + "enum": "gpsProvider_e" + }, + { + "name": "legacyGpsBaud", + "ctype": "uint8_t", + "desc": "Ignored" + }, + { + "name": "gpsSbasMode", + "ctype": "uint8_t", + "desc": "Enum `sbasMode_e` Sets `gpsConfigMutable()->sbasMode` (if `USE_GPS`)", + "units": "Enum", + "enum": "sbasMode_e" + }, + { + "name": "rssiChannel", + "ctype": "uint8_t", + "desc": "Sets `rxConfigMutable()->rssi_channel` (1-based, 0 disables) when <= `MAX_SUPPORTED_RC_CHANNEL_COUNT`", + "units": "Index" + }, + { + "name": "magDeclination", + "ctype": "int16_t", + "desc": "Sets `compassConfigMutable()->mag_declination = value * 10` (if `USE_MAG`)", + "units": "0.1 degrees" + }, + { + "name": "vbatScale", + "ctype": "uint16_t", + "desc": "Sets `batteryMetersConfigMutable()->voltage.scale` (if `USE_ADC`)", + "units": "Scale" + }, + { + "name": "vbatSource", + "ctype": "uint8_t", + "desc": "Enum `batVoltageSource_e` Sets `batteryMetersConfigMutable()->voltageSource` (if `USE_ADC`, validated)", + "units": "Enum", + "enum": "batVoltageSource_e" + }, + { + "name": "cellCount", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->cells` (if `USE_ADC`)", + "units": "Count" + }, + { + "name": "vbatCellDetect", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellDetect` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "vbatMinCell", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "capacityValue", + "ctype": "uint32_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.value`", + "units": "mAh/mWh" + }, + { + "name": "capacityWarning", + "ctype": "uint32_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.warning`", + "units": "mAh/mWh" + }, + { + "name": "capacityCritical", + "ctype": "uint32_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.critical`", + "units": "mAh/mWh" + }, + { + "name": "capacityUnit", + "ctype": "uint8_t", + "desc": "Enum `batCapacityUnit_e` Sets `batteryMetersConfigMutable()->capacity_unit` (validated, updates OSD energy unit if changed)", + "units": "Enum", + "enum": "batCapacityUnit_e" + } + ] + }, + "reply": null, + "notes": "Expects 41 bytes. Performs validation on `vbatSource` and `capacityUnit`.", + "description": "Sets miscellaneous configuration settings, superseding `MSP_SET_MISC`." + }, + "MSP2_INAV_BATTERY_CONFIG": { + "code": 8197, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "vbatScale", + "ctype": "uint16_t", + "desc": "Voltage scale (`batteryMetersConfig()->voltage.scale`)", + "units": "Scale" + }, + { + "name": "vbatSource", + "ctype": "uint8_t", + "desc": "Enum `batVoltageSource_e` Voltage source (`batteryMetersConfig()->voltageSource`)", + "units": "Enum", + "enum": "batVoltageSource_e" + }, + { + "name": "cellCount", + "ctype": "uint8_t", + "desc": "Configured cell count (`currentBatteryProfile->cells`)", + "units": "Count" + }, + { + "name": "vbatCellDetect", + "ctype": "uint16_t", + "desc": "Cell detection voltage (`currentBatteryProfile->voltage.cellDetect`)", + "units": "0.01V" + }, + { + "name": "vbatMinCell", + "ctype": "uint16_t", + "desc": "Min cell voltage (`currentBatteryProfile->voltage.cellMin`)", + "units": "0.01V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint16_t", + "desc": "Max cell voltage (`currentBatteryProfile->voltage.cellMax`)", + "units": "0.01V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint16_t", + "desc": "Warning cell voltage (`currentBatteryProfile->voltage.cellWarning`)", + "units": "0.01V" + }, + { + "name": "currentOffset", + "ctype": "int16_t", + "desc": "Current sensor offset (`batteryMetersConfig()->current.offset`)", + "units": "mV" + }, + { + "name": "currentScale", + "ctype": "int16_t", + "desc": "Current sensor scale (`batteryMetersConfig()->current.scale`)", + "units": "0.1 mV/A" + }, + { + "name": "capacityValue", + "ctype": "uint32_t", + "desc": "Battery capacity (`currentBatteryProfile->capacity.value`)", + "units": "mAh/mWh" + }, + { + "name": "capacityWarning", + "ctype": "uint32_t", + "desc": "Capacity warning threshold (`currentBatteryProfile->capacity.warning`)", + "units": "mAh/mWh" + }, + { + "name": "capacityCritical", + "ctype": "uint32_t", + "desc": "Capacity critical threshold (`currentBatteryProfile->capacity.critical`)", + "units": "mAh/mWh" + }, + { + "name": "capacityUnit", + "ctype": "uint8_t", + "desc": "Enum `batCapacityUnit_e` Capacity unit (`batteryMetersConfig()->capacity_unit`)", + "units": "Enum", + "enum": "batCapacityUnit_e" + } + ] + }, + "notes": "Fields are 0 if `USE_ADC` is not defined.", + "description": "Retrieves the configuration specific to the battery voltage and current sensors and capacity settings for the current battery profile." }, - "reply": null, - "variable_len": true, - "notes": "Requires `MSP_FIRMWARE_UPDATE`. Returns error if storage fails (e.g., out of space, checksum error). Called repeatedly until the entire firmware is transferred. Calls `firmwareUpdateStore()`.", - "description": "Stores a chunk of firmware data received via MSP." - }, - "MSP2_INAV_FWUPDT_EXEC": { - "code": 8245, - "mspv": 2, - "request": { - "payload": [ - { - "name": "updateType", - "ctype": "uint8_t", - "desc": "Type of update (e.g., full flash, specific section - currently ignored/unused)", - "units": "" - } - ] + "MSP2_INAV_SET_BATTERY_CONFIG": { + "code": 8198, + "mspv": 2, + "request": { + "payload": [ + { + "name": "vbatScale", + "ctype": "uint16_t", + "desc": "Sets `batteryMetersConfigMutable()->voltage.scale` (if `USE_ADC`)", + "units": "Scale" + }, + { + "name": "vbatSource", + "ctype": "uint8_t", + "desc": "Enum `batVoltageSource_e` Sets `batteryMetersConfigMutable()->voltageSource` (if `USE_ADC`, validated)", + "units": "Enum", + "enum": "batVoltageSource_e" + }, + { + "name": "cellCount", + "ctype": "uint8_t", + "desc": "Sets `currentBatteryProfileMutable->cells` (if `USE_ADC`)", + "units": "Count" + }, + { + "name": "vbatCellDetect", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellDetect` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "vbatMinCell", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMin` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "vbatMaxCell", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellMax` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "vbatWarningCell", + "ctype": "uint16_t", + "desc": "Sets `currentBatteryProfileMutable->voltage.cellWarning` (if `USE_ADC`)", + "units": "0.01V" + }, + { + "name": "currentOffset", + "ctype": "int16_t", + "desc": "Sets `batteryMetersConfigMutable()->current.offset`", + "units": "mV" + }, + { + "name": "currentScale", + "ctype": "int16_t", + "desc": "Sets `batteryMetersConfigMutable()->current.scale`", + "units": "0.1 mV/A" + }, + { + "name": "capacityValue", + "ctype": "uint32_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.value`", + "units": "mAh/mWh" + }, + { + "name": "capacityWarning", + "ctype": "uint32_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.warning`", + "units": "mAh/mWh" + }, + { + "name": "capacityCritical", + "ctype": "uint32_t", + "desc": "Sets `currentBatteryProfileMutable->capacity.critical`", + "units": "mAh/mWh" + }, + { + "name": "capacityUnit", + "ctype": "uint8_t", + "desc": "Enum `batCapacityUnit_e` Sets `batteryMetersConfigMutable()->capacity_unit` (validated, updates OSD energy unit if changed)", + "units": "Enum", + "enum": "batCapacityUnit_e" + } + ] + }, + "reply": null, + "notes": "Expects 29 bytes. Performs validation on `vbatSource` and `capacityUnit`.", + "description": "Sets the battery voltage/current sensor configuration and capacity settings for the current battery profile." + }, + "MSP2_INAV_RATE_PROFILE": { + "code": 8199, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "throttleMid", + "ctype": "uint8_t", + "desc": "Throttle Midpoint (`currentControlRateProfile->throttle.rcMid8`)", + "units": "" + }, + { + "name": "throttleExpo", + "ctype": "uint8_t", + "desc": "Throttle Expo (`currentControlRateProfile->throttle.rcExpo8`)", + "units": "" + }, + { + "name": "dynamicThrottlePID", + "ctype": "uint8_t", + "desc": "TPA value (`currentControlRateProfile->throttle.dynPID`)", + "units": "" + }, + { + "name": "tpaBreakpoint", + "ctype": "uint16_t", + "desc": "TPA breakpoint (`currentControlRateProfile->throttle.pa_breakpoint`)", + "units": "" + }, + { + "name": "stabRcExpo", + "ctype": "uint8_t", + "desc": "Stabilized Roll/Pitch Expo (`currentControlRateProfile->stabilized.rcExpo8`)", + "units": "" + }, + { + "name": "stabRcYawExpo", + "ctype": "uint8_t", + "desc": "Stabilized Yaw Expo (`currentControlRateProfile->stabilized.rcYawExpo8`)", + "units": "" + }, + { + "name": "stabRollRate", + "ctype": "uint8_t", + "desc": "Stabilized Roll Rate (`currentControlRateProfile->stabilized.rates[FD_ROLL]`)", + "units": "" + }, + { + "name": "stabPitchRate", + "ctype": "uint8_t", + "desc": "Stabilized Pitch Rate (`currentControlRateProfile->stabilized.rates[FD_PITCH]`)", + "units": "" + }, + { + "name": "stabYawRate", + "ctype": "uint8_t", + "desc": "Stabilized Yaw Rate (`currentControlRateProfile->stabilized.rates[FD_YAW]`)", + "units": "" + }, + { + "name": "manualRcExpo", + "ctype": "uint8_t", + "desc": "Manual Roll/Pitch Expo (`currentControlRateProfile->manual.rcExpo8`)", + "units": "" + }, + { + "name": "manualRcYawExpo", + "ctype": "uint8_t", + "desc": "Manual Yaw Expo (`currentControlRateProfile->manual.rcYawExpo8`)", + "units": "" + }, + { + "name": "manualRollRate", + "ctype": "uint8_t", + "desc": "Manual Roll Rate (`currentControlRateProfile->manual.rates[FD_ROLL]`)", + "units": "" + }, + { + "name": "manualPitchRate", + "ctype": "uint8_t", + "desc": "Manual Pitch Rate (`currentControlRateProfile->manual.rates[FD_PITCH]`)", + "units": "" + }, + { + "name": "manualYawRate", + "ctype": "uint8_t", + "desc": "Manual Yaw Rate (`currentControlRateProfile->manual.rates[FD_YAW]`)", + "units": "" + } + ] + }, + "notes": "", + "description": "Retrieves the rates and expos for the current control rate profile, including both stabilized and manual flight modes. Supersedes `MSP_RC_TUNING`." }, - "reply": null, - "notes": "Requires `MSP_FIRMWARE_UPDATE`. Expects 1 byte. Returns error if update cannot start (e.g., not fully received). Calls `firmwareUpdateExec()`. If successful, the device will reboot into the new firmware.", - "description": "Executes the firmware update process (flashes the stored firmware and reboots)." - }, - "MSP2_INAV_FWUPDT_ROLLBACK_PREPARE": { - "code": 8246, - "mspv": 2, - "request": null, - "reply": null, - "notes": "Requires `MSP_FIRMWARE_UPDATE`. Returns error if rollback preparation fails (e.g., no rollback image available). Calls `firmwareUpdateRollbackPrepare()`.", - "description": "Prepares the flight controller to perform a firmware rollback to the previously stored version." - }, - "MSP2_INAV_FWUPDT_ROLLBACK_EXEC": { - "code": 8247, - "mspv": 2, - "request": null, - "reply": null, - "notes": "Requires `MSP_FIRMWARE_UPDATE`. Returns error if rollback cannot start. Calls `firmwareUpdateRollbackExec()`. If successful, the device will reboot into the backup firmware.", - "description": "Executes the firmware rollback process (flashes the stored backup firmware and reboots)." - }, - "MSP2_INAV_SAFEHOME": { - "code": 8248, - "mspv": 2, - "request": { - "payload": [ - { - "name": "safehomeIndex", - "ctype": "uint8_t", - "desc": "Index of the safe home location (0 to `MAX_SAFE_HOMES - 1`)", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "safehomeIndex", - "ctype": "uint8_t", - "desc": "Index requested", - "units": "" - }, - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 if this safe home is enabled", - "units": "" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude (1e7 deg)", - "units": "" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude (1e7 deg)", - "units": "" - } - ] + "MSP2_INAV_SET_RATE_PROFILE": { + "code": 8200, + "mspv": 2, + "request": { + "payload": [ + { + "name": "throttleMid", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->throttle.rcMid8`", + "units": "" + }, + { + "name": "throttleExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->throttle.rcExpo8`", + "units": "" + }, + { + "name": "dynamicThrottlePID", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->throttle.dynPID`", + "units": "" + }, + { + "name": "tpaBreakpoint", + "ctype": "uint16_t", + "desc": "Sets `currentControlRateProfile->throttle.pa_breakpoint`", + "units": "" + }, + { + "name": "stabRcExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rcExpo8`", + "units": "" + }, + { + "name": "stabRcYawExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rcYawExpo8`", + "units": "" + }, + { + "name": "stabRollRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_ROLL]` (constrained)", + "units": "" + }, + { + "name": "stabPitchRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_PITCH]` (constrained)", + "units": "" + }, + { + "name": "stabYawRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->stabilized.rates[FD_YAW]` (constrained)", + "units": "" + }, + { + "name": "manualRcExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->manual.rcExpo8`", + "units": "" + }, + { + "name": "manualRcYawExpo", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->manual.rcYawExpo8`", + "units": "" + }, + { + "name": "manualRollRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->manual.rates[FD_ROLL]` (constrained)", + "units": "" + }, + { + "name": "manualPitchRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->manual.rates[FD_PITCH]` (constrained)", + "units": "" + }, + { + "name": "manualYawRate", + "ctype": "uint8_t", + "desc": "Sets `currentControlRateProfile->manual.rates[FD_YAW]` (constrained)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 15 bytes. Constraints applied to rates based on axis.", + "description": "Sets the rates and expos for the current control rate profile (stabilized and manual). Supersedes `MSP_SET_RC_TUNING`." + }, + "MSP2_INAV_AIR_SPEED": { + "code": 8201, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "airspeed", + "ctype": "uint32_t", + "desc": "Estimated/measured airspeed (`getAirspeedEstimate()`, cm/s). 0 if unavailable", + "units": "cm/s" + } + ] + }, + "notes": "Requires `USE_PITOT`; returns 0 when pitot functionality is not enabled or calibrated.", + "description": "Retrieves the estimated or measured airspeed." + }, + "MSP2_INAV_OUTPUT_MAPPING": { + "code": 8202, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "usageFlags", + "ctype": "uint8_t", + "desc": "Timer usage flags (lower 8 bits of `timerHardware[i].usageFlags`, e.g. `TIM_USE_MOTOR`, `TIM_USE_SERVO`)", + "units": "" + } + ], + "repeating": "for each Motor/Servo timer" + }, + "variable_len": "for each Motor/Servo timer", + "notes": "Superseded by `MSP2_INAV_OUTPUT_MAPPING_EXT2`. Only includes timers *not* used for PPM/PWM input.", + "description": "Retrieves the output mapping configuration (identifies which timer outputs are used for Motors/Servos). Legacy version sending only 8-bit usage flags." + }, + "MSP2_INAV_MC_BRAKING": { + "code": 8203, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "brakingSpeedThreshold", + "ctype": "uint16_t", + "desc": "Speed above which braking engages (`navConfig()->mc.braking_speed_threshold`)", + "units": "cm/s" + }, + { + "name": "brakingDisengageSpeed", + "ctype": "uint16_t", + "desc": "Speed below which braking disengages (`navConfig()->mc.braking_disengage_speed`)", + "units": "cm/s" + }, + { + "name": "brakingTimeout", + "ctype": "uint16_t", + "desc": "Timeout before braking force reduces (`navConfig()->mc.braking_timeout`)", + "units": "ms" + }, + { + "name": "brakingBoostFactor", + "ctype": "uint8_t", + "desc": "Boost factor applied during braking (`navConfig()->mc.braking_boost_factor`)", + "units": "%" + }, + { + "name": "brakingBoostTimeout", + "ctype": "uint16_t", + "desc": "Timeout for the boost factor (`navConfig()->mc.braking_boost_timeout`)", + "units": "ms" + }, + { + "name": "brakingBoostSpeedThreshold", + "ctype": "uint16_t", + "desc": "Speed threshold for boost engagement (`navConfig()->mc.braking_boost_speed_threshold`)", + "units": "cm/s" + }, + { + "name": "brakingBoostDisengageSpeed", + "ctype": "uint16_t", + "desc": "Speed threshold for boost disengagement (`navConfig()->mc.braking_boost_disengage_speed`)", + "units": "cm/s" + }, + { + "name": "brakingBankAngle", + "ctype": "uint8_t", + "desc": "Maximum bank angle allowed during braking (`navConfig()->mc.braking_bank_angle`)", + "units": "degrees" + } + ] + }, + "notes": "Payload is empty if `USE_MR_BRAKING_MODE` is not defined.", + "description": "Retrieves configuration parameters for the multirotor braking mode feature." }, - "notes": "Requires `USE_SAFE_HOME`. Used by `mspFcSafeHomeOutCommand`. See `MSP2_INAV_SET_SAFEHOME` for setting.", - "description": "Get or Set configuration for a specific Safe Home location." - }, - "MSP2_INAV_SET_SAFEHOME": { - "code": 8249, - "mspv": 2, - "request": { - "payload": [ - { - "name": "safehomeIndex", - "ctype": "uint8_t", - "desc": "Index of the safe home location (0 to `MAX_SAFE_HOMES - 1`)", - "units": "" - }, - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 to enable this safe home", - "units": "" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Latitude (1e7 deg)", - "units": "" + "MSP2_INAV_SET_MC_BRAKING": { + "code": 8204, + "mspv": 2, + "request": { + "payload": [ + { + "name": "brakingSpeedThreshold", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->mc.braking_speed_threshold`", + "units": "cm/s" + }, + { + "name": "brakingDisengageSpeed", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->mc.braking_disengage_speed`", + "units": "cm/s" + }, + { + "name": "brakingTimeout", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->mc.braking_timeout`", + "units": "ms" + }, + { + "name": "brakingBoostFactor", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->mc.braking_boost_factor`", + "units": "%" + }, + { + "name": "brakingBoostTimeout", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->mc.braking_boost_timeout`", + "units": "ms" + }, + { + "name": "brakingBoostSpeedThreshold", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->mc.braking_boost_speed_threshold`", + "units": "cm/s" + }, + { + "name": "brakingBoostDisengageSpeed", + "ctype": "uint16_t", + "desc": "Sets `navConfigMutable()->mc.braking_boost_disengage_speed`", + "units": "cm/s" + }, + { + "name": "brakingBankAngle", + "ctype": "uint8_t", + "desc": "Sets `navConfigMutable()->mc.braking_bank_angle`", + "units": "degrees" + } + ] + }, + "reply": null, + "notes": "Expects 14 bytes. Returns error if `USE_MR_BRAKING_MODE` is not defined.", + "description": "Sets configuration parameters for the multirotor braking mode feature." + }, + "MSP2_INAV_OUTPUT_MAPPING_EXT": { + "code": 8205, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "timerId", + "ctype": "uint8_t", + "desc": "Hardware timer identifier (e.g., `TIM1`, `TIM2`). Value depends on target", + "units": "" + }, + { + "name": "usageFlags", + "ctype": "uint8_t", + "desc": "Timer usage flags (lower 8 bits of `timerHardware[i].usageFlags`, e.g. `TIM_USE_MOTOR`, `TIM_USE_SERVO`)", + "units": "" + } + ], + "repeating": "for each Motor/Servo timer" + }, + "variable_len": "for each Motor/Servo timer", + "notes": "Usage flags are truncated to 8 bits. `timerId` mapping is target-specific.", + "description": "Retrieves extended output mapping configuration (timer ID and usage flags). Obsolete, use `MSP2_INAV_OUTPUT_MAPPING_EXT2`." + }, + "MSP2_INAV_TIMER_OUTPUT_MODE": { + "code": 8206, + "mspv": 2, + "request": null, + "reply": null, + "variable_len": true, + "notes": "Non-SITL only. HARDWARE_TIMER_DEFINITION_COUNT is target specific. Returns MSP_RESULT_ACK on success, MSP_RESULT_ERROR on invalid timer index.", + "description": "Reads timer output mode overrides.", + "variants": { + "dataSize == 0": { + "description": "List all timers", + "request": null, + "reply": { + "payload": [ + { + "name": "timerIndex", + "ctype": "uint8_t", + "desc": "Timer index" + }, + { + "name": "outputMode", + "ctype": "uint8_t", + "enum": "outputMode_e", + "desc": "OUTPUT_MODE_*" + } + ], + "repeating": "HARDWARE_TIMER_DEFINITION_COUNT" + } }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Longitude (1e7 deg)", - "units": "" + "dataSize == 1": { + "description": "Query one timer", + "request": { + "payload": [ + { + "name": "timerIndex", + "ctype": "uint8_t", + "desc": "0..HARDWARE_TIMER_DEFINITION_COUNT-1" + } + ] + }, + "reply": { + "payload": [ + { + "name": "timerIndex", + "ctype": "uint8_t", + "desc": "Echoed timer index" + }, + { + "name": "outputMode", + "ctype": "uint8_t", + "enum": "outputMode_e", + "desc": "OUTPUT_MODE_*" + } + ] + } } - ] + } }, - "reply": null, - "notes": "Requires `USE_SAFE_HOME`. Expects 10 bytes. Returns error if index invalid. Resets corresponding FW autoland approach if `USE_FW_AUTOLAND` is enabled.", - "description": "Sets the configuration for a specific Safe Home location." - }, - "MSP2_INAV_MISC2": { - "code": 8250, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "uptimeSeconds", - "ctype": "uint32_t", - "desc": "Time since boot (`micros() / 1000000`)", - "units": "Seconds" - }, - { - "name": "flightTimeSeconds", - "ctype": "uint32_t", - "desc": "Accumulated flight time (`getFlightTime()`)", - "units": "Seconds" - }, - { - "name": "throttlePercent", - "ctype": "uint8_t", - "desc": "Current throttle output percentage (`getThrottlePercent(true)`)", - "units": "%" - }, - { - "name": "autoThrottleFlag", - "ctype": "uint8_t", - "desc": "1 if navigation is controlling throttle, 0 otherwise (`navigationIsControllingThrottle()`)", - "units": "Boolean" - } - ] + "MSP2_INAV_SET_TIMER_OUTPUT_MODE": { + "code": 8207, + "mspv": 2, + "request": { + "payload": [ + { + "name": "timerIndex", + "ctype": "uint8_t", + "desc": "Index of the hardware timer definition", + "units": "" + }, + { + "name": "outputMode", + "ctype": "uint8_t", + "desc": "Output mode override (`outputMode_e` enum) to set", + "units": "", + "enum": "outputMode_e" + } + ] + }, + "reply": null, + "notes": "Only available on non-SITL builds. Expects 2 bytes. Returns error if `timerIndex` is invalid.", + "description": "Set the output mode override for a specific hardware timer." + }, + "MSP2_INAV_MIXER": { + "code": 8208, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "motorDirectionInverted", + "ctype": "uint8_t", + "desc": "Boolean: 1 if motor direction is reversed globally (`mixerConfig()->motorDirectionInverted`)", + "units": "" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Always 0 (Was yaw jump prevention limit)", + "units": "", + "value": 0 + }, + { + "name": "motorStopOnLow", + "ctype": "uint8_t", + "desc": "Boolean: 1 if motors stop at minimum throttle (`mixerConfig()->motorstopOnLow`)", + "units": "" + }, + { + "name": "platformType", + "ctype": "uint8_t", + "desc": "Enum (`mixerConfig()->platformType`)", + "units": "", + "enum": "flyingPlatformType_e" + }, + { + "name": "hasFlaps", + "ctype": "uint8_t", + "desc": "Boolean: 1 if the current mixer configuration includes flaps (`mixerConfig()->hasFlaps`)", + "units": "" + }, + { + "name": "appliedMixerPreset", + "ctype": "int16_t", + "desc": "Enum (`mixerPreset_e`): Mixer preset currently applied (`mixerConfig()->appliedMixerPreset`) WARNING: cannot figure where this is", + "units": "", + "enum": "mixerPreset_e" + }, + { + "name": "maxMotors", + "ctype": "uint8_t", + "desc": "Constant: Maximum motors supported (`MAX_SUPPORTED_MOTORS`)", + "units": "" + }, + { + "name": "maxServos", + "ctype": "uint8_t", + "desc": "Constant: Maximum servos supported (`MAX_SUPPORTED_SERVOS`)", + "units": "" + } + ] + }, + "notes": "", + "description": "Retrieves INAV-specific mixer configuration details." }, - "notes": "", - "description": "Retrieves miscellaneous runtime information including timers and throttle status." - }, - "MSP2_INAV_LOGIC_CONDITIONS_SINGLE": { - "code": 8251, - "mspv": 2, - "request": { - "payload": [ - { - "name": "conditionIndex", - "ctype": "uint8_t", - "desc": "Index of the condition to retrieve (0 to `MAX_LOGIC_CONDITIONS - 1`)", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 if enabled", - "units": "" - }, - { - "name": "activatorId", - "ctype": "int8_t", - "desc": "Activator ID (-1/255 if none)", - "units": "" - }, - { - "name": "operation", - "ctype": "uint8_t", - "desc": "Enum `logicOperation_e` Logical operation", - "units": "", - "enum": "logicOperation_e" - }, - { - "name": "operandAType", - "ctype": "uint8_t", - "desc": "Enum `logicOperandType_e` Type of operand A", - "units": "", - "enum": "logicOperandType_e" - }, - { - "name": "operandAValue", - "ctype": "int32_t", - "desc": "Value/ID of operand A", - "units": "" - }, - { - "name": "operandBType", - "ctype": "uint8_t", - "desc": "Enum `logicOperandType_e` Type of operand B", - "units": "", - "enum": "logicOperandType_e" + "MSP2_INAV_SET_MIXER": { + "code": 8209, + "mspv": 2, + "request": { + "payload": [ + { + "name": "motorDirectionInverted", + "ctype": "uint8_t", + "desc": "Sets `mixerConfigMutable()->motorDirectionInverted`", + "units": "" + }, + { + "name": "reserved1", + "ctype": "uint8_t", + "desc": "Ignored", + "units": "" + }, + { + "name": "motorStopOnLow", + "ctype": "uint8_t", + "desc": "Sets `mixerConfigMutable()->motorstopOnLow`", + "units": "" + }, + { + "name": "platformType", + "ctype": "uint8_t", + "desc": "Sets `mixerConfigMutable()->platformType`", + "units": "", + "enum": "flyingPlatformType_e" + }, + { + "name": "hasFlaps", + "ctype": "uint8_t", + "desc": "Sets `mixerConfigMutable()->hasFlaps`", + "units": "" + }, + { + "name": "appliedMixerPreset", + "ctype": "int16_t", + "desc": "Sets `mixerConfigMutable()->appliedMixerPreset`", + "units": "" + }, + { + "name": "maxMotors", + "ctype": "uint8_t", + "desc": "Ignored", + "units": "" + }, + { + "name": "maxServos", + "ctype": "uint8_t", + "desc": "Ignored", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 9 bytes. Calls `mixerUpdateStateFlags()`.", + "description": "Sets INAV-specific mixer configuration details." + }, + "MSP2_INAV_OSD_LAYOUTS": { + "code": 8210, + "mspv": 2, + "request": null, + "reply": null, + "variants": { + "dataSize == 0": { + "description": "Query layout/item counts", + "request": null, + "reply": { + "payload": [ + { + "name": "layoutCount", + "ctype": "uint8_t", + "desc": "Number of OSD layouts (`OSD_LAYOUT_COUNT`)" + }, + { + "name": "itemCount", + "ctype": "uint8_t", + "desc": "Number of OSD items per layout (`OSD_ITEM_COUNT`)" + } + ] + } }, - { - "name": "operandBValue", - "ctype": "int32_t", - "desc": "Value/ID of operand B", - "units": "" + "dataSize == 1": { + "description": "Fetch all item positions for a layout", + "request": { + "payload": [ + { + "name": "layoutIndex", + "ctype": "uint8_t", + "desc": "Layout index (0 to `OSD_LAYOUT_COUNT - 1`)" + } + ] + }, + "reply": { + "payload": [ + { + "name": "itemPosition", + "ctype": "uint16_t", + "desc": "Packed X/Y position (`osdLayoutsConfig()->item_pos[layoutIndex][item]`)", + "units": "packed coords" + } + ], + "repeating": "OSD_ITEM_COUNT" + } }, - { - "name": "flags", - "ctype": "uint8_t", - "desc": "Bitmask: Condition flags (`logicConditionFlags_e`)", - "units": "Bitmask", - "bitmask": true + "dataSize == 3": { + "description": "Fetch a single item position", + "request": { + "payload": [ + { + "name": "layoutIndex", + "ctype": "uint8_t", + "desc": "Layout index (0 to `OSD_LAYOUT_COUNT - 1`)" + }, + { + "name": "itemIndex", + "ctype": "uint16_t", + "desc": "OSD item index (0 to `OSD_ITEM_COUNT - 1`)" + } + ] + }, + "reply": { + "payload": [ + { + "name": "itemPosition", + "ctype": "uint16_t", + "desc": "Packed X/Y position (`osdLayoutsConfig()->item_pos[layoutIndex][itemIndex]`)", + "units": "packed coords" + } + ] + } } - ] + }, + "notes": "Requires `USE_OSD`. Returns `MSP_RESULT_ACK` on success, `MSP_RESULT_ERROR` if indexes are out of range.", + "description": "Retrieves OSD layout metadata or item positions for specific layouts/items." }, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Used by `mspFcLogicConditionCommand`.", - "description": "Gets the configuration for a single Logic Condition by its index." - }, - "MSP2_INAV_ESC_RPM": { - "code": 8256, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "escRpm", - "ctype": "uint32_t", - "desc": "RPM reported by the ESC", - "units": "RPM" - } - ], - "repeating": "getMotorCount()" + "MSP2_INAV_OSD_SET_LAYOUT_ITEM": { + "code": 8211, + "mspv": 2, + "request": { + "payload": [ + { + "name": "layoutIndex", + "ctype": "uint8_t", + "desc": "Index of the OSD layout (0 to `OSD_LAYOUT_COUNT - 1`)", + "units": "Index" + }, + { + "name": "itemIndex", + "ctype": "uint8_t", + "desc": "Index of the OSD item", + "units": "Index" + }, + { + "name": "itemPosition", + "ctype": "uint16_t", + "desc": "Packed X/Y position using `OSD_POS(x, y)` with `OSD_VISIBLE_FLAG` bit", + "units": "Coordinates" + } + ] + }, + "reply": null, + "notes": "Requires `USE_OSD`. Expects 4 bytes. Returns error if indexes are invalid. If the modified layout is not the currently active one, it temporarily overrides the active layout for 10 seconds to show the change. Otherwise, triggers a full OSD redraw.", + "description": "Sets the position of a single OSD item within a specific layout." + }, + "MSP2_INAV_OSD_ALARMS": { + "code": 8212, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "rssiAlarm", + "ctype": "uint8_t", + "desc": "RSSI alarm threshold (`osdConfig()->rssi_alarm`)", + "units": "%" + }, + { + "name": "timerAlarm", + "ctype": "uint16_t", + "desc": "Timer alarm threshold (`osdConfig()->time_alarm`)", + "units": "seconds" + }, + { + "name": "altAlarm", + "ctype": "uint16_t", + "desc": "Altitude alarm threshold (`osdConfig()->alt_alarm`)", + "units": "meters" + }, + { + "name": "distAlarm", + "ctype": "uint16_t", + "desc": "Distance alarm threshold (`osdConfig()->dist_alarm`)", + "units": "meters" + }, + { + "name": "negAltAlarm", + "ctype": "uint16_t", + "desc": "Negative altitude alarm threshold (`osdConfig()->neg_alt_alarm`)", + "units": "meters" + }, + { + "name": "gForceAlarm", + "ctype": "uint16_t", + "desc": "G-force alarm threshold (`osdConfig()->gforce_alarm * 1000`)", + "units": "G * 1000" + }, + { + "name": "gForceAxisMinAlarm", + "ctype": "int16_t", + "desc": "Min G-force per-axis alarm (`osdConfig()->gforce_axis_alarm_min * 1000`)", + "units": "G * 1000" + }, + { + "name": "gForceAxisMaxAlarm", + "ctype": "int16_t", + "desc": "Max G-force per-axis alarm (`osdConfig()->gforce_axis_alarm_max * 1000`)", + "units": "G * 1000" + }, + { + "name": "currentAlarm", + "ctype": "uint8_t", + "desc": "Current draw alarm threshold (`osdConfig()->current_alarm`)", + "units": "A" + }, + { + "name": "imuTempMinAlarm", + "ctype": "int16_t", + "desc": "Min IMU temperature alarm (`osdConfig()->imu_temp_alarm_min`)", + "units": "degrees C" + }, + { + "name": "imuTempMaxAlarm", + "ctype": "int16_t", + "desc": "Max IMU temperature alarm (`osdConfig()->imu_temp_alarm_max`)", + "units": "degrees C" + }, + { + "name": "baroTempMinAlarm", + "ctype": "int16_t", + "desc": "Min Baro temperature alarm (`osdConfig()->baro_temp_alarm_min`). 0 if `USE_BARO` disabled", + "units": "degrees C" + }, + { + "name": "baroTempMaxAlarm", + "ctype": "int16_t", + "desc": "Max Baro temperature alarm (`osdConfig()->baro_temp_alarm_max`). 0 if `USE_BARO` disabled", + "units": "degrees C" + }, + { + "name": "adsbWarnDistance", + "ctype": "uint16_t", + "desc": "ADSB warning distance (`osdConfig()->adsb_distance_warning`). 0 if `USE_ADSB` disabled", + "units": "meters" + }, + { + "name": "adsbAlertDistance", + "ctype": "uint16_t", + "desc": "ADSB alert distance (`osdConfig()->adsb_distance_alert`). 0 if `USE_ADSB` disabled", + "units": "meters" + } + ] + }, + "notes": "Requires `USE_OSD`.", + "description": "Retrieves OSD alarm threshold settings." }, - "variable_len": "getMotorCount()", - "notes": "Requires `USE_ESC_SENSOR`. Payload size depends on the number of detected motors with telemetry.", - "description": "Retrieves the RPM reported by each ESC via telemetry." - }, - "MSP2_INAV_ESC_TELEM": { - "code": 8257, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "motorCount", - "ctype": "uint8_t", - "desc": "Number of motors reporting telemetry (`getMotorCount()`)", - "units": "" - }, - { - "name": "escData", - "desc": "Array of `escSensorData_t` structures containing voltage, current, temp, RPM, errors etc. for each ESC", - "ctype": "escSensorData_t", - "array": true, - "array_size": 0, - "units": "" - } - ] + "MSP2_INAV_OSD_SET_ALARMS": { + "code": 8213, + "mspv": 2, + "request": { + "payload": [ + { + "name": "rssiAlarm", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->rssi_alarm", + "units": "%" + }, + { + "name": "timerAlarm", + "ctype": "uint16_t", + "desc": "Sets `osdConfigMutable()->time_alarm", + "units": "seconds" + }, + { + "name": "altAlarm", + "ctype": "uint16_t", + "desc": "Sets `osdConfigMutable()->alt_alarm", + "units": "meters" + }, + { + "name": "distAlarm", + "ctype": "uint16_t", + "desc": "Sets `osdConfigMutable()->dist_alarm", + "units": "meters" + }, + { + "name": "negAltAlarm", + "ctype": "uint16_t", + "desc": "Sets `osdConfigMutable()->neg_alt_alarm`", + "units": "meters" + }, + { + "name": "gForceAlarm", + "ctype": "uint16_t", + "desc": "Sets `osdConfigMutable()->gforce_alarm = value / 1000.0f`", + "units": "G * 1000" + }, + { + "name": "gForceAxisMinAlarm", + "ctype": "int16_t", + "desc": "Sets `osdConfigMutable()->gforce_axis_alarm_min = value / 1000.0f`", + "units": "G * 1000" + }, + { + "name": "gForceAxisMaxAlarm", + "ctype": "int16_t", + "desc": "Sets `osdConfigMutable()->gforce_axis_alarm_max = value / 1000.0f`", + "units": "G * 1000" + }, + { + "name": "currentAlarm", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->current_alarm`", + "units": "A" + }, + { + "name": "imuTempMinAlarm", + "ctype": "int16_t", + "desc": "Sets `osdConfigMutable()->imu_temp_alarm_min`", + "units": "degrees C" + }, + { + "name": "imuTempMaxAlarm", + "ctype": "int16_t", + "desc": "Sets `osdConfigMutable()->imu_temp_alarm_max`", + "units": "degrees C" + }, + { + "name": "baroTempMinAlarm", + "ctype": "int16_t", + "desc": "Sets `osdConfigMutable()->baro_temp_alarm_min` (if `USE_BARO`)", + "units": "degrees C" + }, + { + "name": "baroTempMaxAlarm", + "ctype": "int16_t", + "desc": "Sets `osdConfigMutable()->baro_temp_alarm_max` (if `USE_BARO`)", + "units": "degrees C" + } + ] + }, + "reply": null, + "notes": "Requires `USE_OSD`. Expects 24 bytes. ADSB alarms are not settable via this message.", + "description": "Sets OSD alarm threshold settings." + }, + "MSP2_INAV_OSD_PREFERENCES": { + "code": 8214, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "videoSystem", + "ctype": "uint8_t", + "desc": "Enum `videoSystem_e`: Video system (Auto/PAL/NTSC) (`osdConfig()->video_system`)", + "units": "", + "enum": "videoSystem_e" + }, + { + "name": "mainVoltageDecimals", + "ctype": "uint8_t", + "desc": "Count: Decimal places for main voltage display (`osdConfig()->main_voltage_decimals`)", + "units": "" + }, + { + "name": "ahiReverseRoll", + "ctype": "uint8_t", + "desc": "Boolean: Reverse roll direction on Artificial Horizon (`osdConfig()->ahi_reverse_roll`)", + "units": "" + }, + { + "name": "crosshairsStyle", + "ctype": "uint8_t", + "desc": "Enum `osd_crosshairs_style_e`: Style of the center crosshairs (`osdConfig()->crosshairs_style`)", + "units": "", + "enum": "osd_crosshairs_style_e" + }, + { + "name": "leftSidebarScroll", + "ctype": "uint8_t", + "desc": "Enum `osd_sidebar_scroll_e`: Left sidebar scroll behavior (`osdConfig()->left_sidebar_scroll`)", + "units": "", + "enum": "osd_sidebar_scroll_e" + }, + { + "name": "rightSidebarScroll", + "ctype": "uint8_t", + "desc": "Enum `osd_sidebar_scroll_e`: Right sidebar scroll behavior (`osdConfig()->right_sidebar_scroll`)", + "units": "", + "enum": "osd_sidebar_scroll_e" + }, + { + "name": "sidebarScrollArrows", + "ctype": "uint8_t", + "desc": "Boolean: Show arrows for scrollable sidebars (`osdConfig()->sidebar_scroll_arrows`)", + "units": "" + }, + { + "name": "units", + "ctype": "uint8_t", + "desc": "Enum: `osd_unit_e` Measurement units (Metric/Imperial) (`osdConfig()->units`)", + "units": "", + "enum": "osd_unit_e" + }, + { + "name": "statsEnergyUnit", + "ctype": "uint8_t", + "desc": "Enum `osd_stats_energy_unit_e`: Unit for energy display in post-flight stats (`osdConfig()->stats_energy_unit`)", + "units": "", + "enum": "osd_stats_energy_unit_e" + } + ] + }, + "notes": "Requires `USE_OSD`.", + "description": "Retrieves OSD display preferences (video system, units, styles, etc.)." }, - "variable_len": true, - "notes": "Requires `USE_ESC_SENSOR`. See `escSensorData_t` in `sensors/esc_sensor.h` for the exact structure fields.", - "description": "Retrieves the full telemetry data structure reported by each ESC." - }, - "MSP2_INAV_LED_STRIP_CONFIG_EX": { - "code": 8264, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "ledConfig", - "ctype": "ledConfig_t", - "desc": "Raw `ledConfig_t` structure (6 bytes) holding position, function, overlay, color, direction, and params bitfields (`io/ledstrip.h`).", - "units": "" - } - ], - "repeating": "LED_MAX_STRIP_LENGTH" + "MSP2_INAV_OSD_SET_PREFERENCES": { + "code": 8215, + "mspv": 2, + "request": { + "payload": [ + { + "name": "videoSystem", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->video_system`", + "units": "", + "enum": "videoSystem_e" + }, + { + "name": "mainVoltageDecimals", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->main_voltage_decimals`", + "units": "" + }, + { + "name": "ahiReverseRoll", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->ahi_reverse_roll`", + "units": "" + }, + { + "name": "crosshairsStyle", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->crosshairs_style`", + "units": "", + "enum": "osd_crosshairs_style_e" + }, + { + "name": "leftSidebarScroll", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->left_sidebar_scroll`", + "units": "", + "enum": "osd_sidebar_scroll_e" + }, + { + "name": "rightSidebarScroll", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->right_sidebar_scroll`", + "units": "", + "enum": "osd_sidebar_scroll_e" + }, + { + "name": "sidebarScrollArrows", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->sidebar_scroll_arrows`", + "units": "" + }, + { + "name": "units", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->units` (enum `osd_unit_e`)", + "units": "", + "enum": "osd_unit_e" + }, + { + "name": "statsEnergyUnit", + "ctype": "uint8_t", + "desc": "Sets `osdConfigMutable()->stats_energy_unit`", + "units": "", + "enum": "osd_stats_energy_unit_e" + } + ] + }, + "reply": null, + "notes": "Requires `USE_OSD`. Expects 9 bytes. Triggers a full OSD redraw.", + "description": "Sets OSD display preferences." }, - "variable_len": "LED_MAX_STRIP_LENGTH", - "notes": "Requires `USE_LED_STRIP`. See `ledConfig_t` in `io/ledstrip.h` for structure fields (position, function, overlay, color, direction, params).", - "description": "Retrieves the full configuration for each LED on the strip using the `ledConfig_t` structure. Supersedes `MSP_LED_STRIP_CONFIG`." - }, - "MSP2_INAV_SET_LED_STRIP_CONFIG_EX": { - "code": 8265, - "mspv": 2, - "request": { - "payload": [ - { - "name": "ledIndex", - "ctype": "uint8_t", - "desc": "Index of the LED to configure (0 to `LED_MAX_STRIP_LENGTH - 1`)", - "units": "" - }, - { - "name": "ledConfig", - "ctype": "ledConfig_t", - "desc": "Raw `ledConfig_t` structure (6 bytes) mirroring the firmware layout.", - "units": "" - } - ] + "MSP2_INAV_SELECT_BATTERY_PROFILE": { + "code": 8216, + "mspv": 2, + "request": { + "payload": [ + { + "name": "batteryProfileIndex", + "ctype": "uint8_t", + "desc": "Index of the battery profile to activate (0-based)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 1 byte. Will fail if armed. Calls `setConfigBatteryProfileAndWriteEEPROM()`.", + "description": "Selects the active battery profile and saves configuration." + }, + "MSP2_INAV_DEBUG": { + "code": 8217, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "debugValues", + "desc": "Values from the `debug` array (signed, typically 8 entries)", + "ctype": "int32_t", + "array": true, + "array_size": 8, + "array_size_define": "DEBUG32_VALUE_COUNT", + "units": "" + } + ] + }, + "variable_len": true, + "notes": "`DEBUG32_VALUE_COUNT` is usually 8.", + "description": "Retrieves values from the firmware's 32-bit `debug[]` array. Supersedes `MSP_DEBUG`." + }, + "MSP2_BLACKBOX_CONFIG": { + "code": 8218, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "blackboxSupported", + "ctype": "uint8_t", + "desc": "Boolean: 1 if Blackbox is supported (`USE_BLACKBOX`), 0 otherwise", + "units": "" + }, + { + "name": "blackboxDevice", + "ctype": "uint8_t", + "desc": "Enum `BlackboxDevice`: Target device for logging (`blackboxConfig()->device`). 0 if not supported", + "units": "", + "enum": "BlackboxDevice" + }, + { + "name": "blackboxRateNum", + "ctype": "uint16_t", + "desc": "Numerator for logging rate divider (`blackboxConfig()->rate_num`). 0 if not supported", + "units": "" + }, + { + "name": "blackboxRateDenom", + "ctype": "uint16_t", + "desc": "Denominator for logging rate divider (`blackboxConfig()->rate_denom`). 0 if not supported", + "units": "" + }, + { + "name": "blackboxIncludeFlags", + "ctype": "uint32_t", + "desc": "Bitmask: Flags for fields included/excluded from logging (`blackboxConfig()->includeFlags`)", + "units": "", + "bitmask": true + } + ] + }, + "notes": "If `USE_BLACKBOX` is disabled, only the first four fields are returned (all zero).", + "description": "Retrieves the Blackbox configuration. Supersedes `MSP_BLACKBOX_CONFIG`." }, - "reply": null, - "notes": "Requires `USE_LED_STRIP`. Expects `1 + sizeof(ledConfig_t)` bytes. Returns error if index invalid. Calls `reevaluateLedConfig()`.", - "description": "Sets the configuration for a single LED on the strip using the `ledConfig_t` structure. Supersedes `MSP_SET_LED_STRIP_CONFIG`." - }, - "MSP2_INAV_FW_APPROACH": { - "code": 8266, - "mspv": 2, - "request": { - "payload": [ - { - "name": "approachIndex", - "ctype": "uint8_t", - "desc": "Index of the approach setting (0 to `MAX_FW_LAND_APPOACH_SETTINGS - 1`)", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "approachIndex", - "ctype": "uint8_t", - "desc": "Index requested", - "units": "Index" - }, - { - "name": "approachAlt", - "ctype": "int32_t", - "desc": "Signed altitude for the approach phase (`navFwAutolandApproach_t.approachAlt`)", - "units": "cm" - }, - { - "name": "landAlt", - "ctype": "int32_t", - "desc": "Signed altitude for the final landing phase (`navFwAutolandApproach_t.landAlt`)", - "units": "cm" - }, - { - "name": "approachDirection", - "ctype": "uint8_t", - "desc": "Enum `fwAutolandApproachDirection_e`: Direction of approach (From WP, Specific Heading)", - "units": "Enum", - "enum": "fwAutolandApproachDirection_e" - }, - { - "name": "landHeading1", - "ctype": "int16_t", - "desc": "Primary landing heading (if approachDirection requires it)", - "units": "degrees" - }, - { - "name": "landHeading2", - "ctype": "int16_t", - "desc": "Secondary landing heading (if approachDirection requires it)", - "units": "degrees" - }, - { - "name": "isSeaLevelRef", - "ctype": "uint8_t", - "desc": "1 if altitudes are relative to sea level, 0 if relative to home", - "units": "Boolean" - } - ] + "MSP2_SET_BLACKBOX_CONFIG": { + "code": 8219, + "mspv": 2, + "request": { + "payload": [ + { + "name": "blackboxDevice", + "ctype": "uint8_t", + "desc": "Sets `blackboxConfigMutable()->device`", + "units": "", + "enum": "BlackboxDevice" + }, + { + "name": "blackboxRateNum", + "ctype": "uint16_t", + "desc": "Sets `blackboxConfigMutable()->rate_num`", + "units": "" + }, + { + "name": "blackboxRateDenom", + "ctype": "uint16_t", + "desc": "Sets `blackboxConfigMutable()->rate_denom`", + "units": "" + }, + { + "name": "blackboxIncludeFlags", + "ctype": "uint32_t", + "desc": "Sets `blackboxConfigMutable()->includeFlags`", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_BLACKBOX`. Expects 9 bytes. Returns error if Blackbox is currently logging (`!blackboxMayEditConfig()`).", + "description": "Sets the Blackbox configuration. Supersedes `MSP_SET_BLACKBOX_CONFIG`." + }, + "MSP2_INAV_TEMP_SENSOR_CONFIG": { + "code": 8220, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "type", + "ctype": "uint8_t", + "desc": "Enum (`tempSensorType_e`): Type of the temperature sensor", + "units": "", + "enum": "tempSensorType_e" + }, + { + "name": "address", + "ctype": "uint64_t", + "desc": "Sensor address/ID (e.g., for 1-Wire sensors)", + "units": "" + }, + { + "name": "alarmMin", + "ctype": "int16_t", + "desc": "Min temperature alarm threshold (`sensorConfig->alarm_min`)", + "units": "0.1Β°C" + }, + { + "name": "alarmMax", + "ctype": "int16_t", + "desc": "Max temperature alarm threshold (`sensorConfig->alarm_max`)", + "units": "0.1Β°C" + }, + { + "name": "osdSymbol", + "ctype": "uint8_t", + "desc": "Index: OSD symbol to use for this sensor (0 to `TEMP_SENSOR_SYM_COUNT`)", + "units": "" + }, + { + "name": "label", + "desc": "User-defined label for the sensor", + "ctype": "char", + "array": true, + "array_size": 4, + "array_size_define": "TEMPERATURE_LABEL_LEN", + "units": "" + } + ], + "repeating": "MAX_TEMP_SENSORS" + }, + "variable_len": "MAX_TEMP_SENSORS", + "notes": "Requires `USE_TEMPERATURE_SENSOR`.", + "description": "Retrieves the configuration for all onboard temperature sensors." }, - "notes": "Requires `USE_FW_AUTOLAND`. Used by `mspFwApproachOutCommand`. See `MSP2_INAV_SET_FW_APPROACH` for setting.", - "description": "Get or Set configuration for a specific Fixed Wing Autoland approach." - }, - "MSP2_INAV_SET_FW_APPROACH": { - "code": 8267, - "mspv": 2, - "request": { - "payload": [ - { - "name": "approachIndex", - "ctype": "uint8_t", - "desc": "Index of the approach setting (0 to `MAX_FW_LAND_APPOACH_SETTINGS - 1`)", - "units": "Index" - }, - { - "name": "approachAlt", - "ctype": "int32_t", - "desc": "Signed approach altitude (`navFwAutolandApproach_t.approachAlt`)", - "units": "cm" - }, - { - "name": "landAlt", - "ctype": "int32_t", - "desc": "Signed landing altitude (`navFwAutolandApproach_t.landAlt`)", - "units": "cm" - }, - { - "name": "approachDirection", - "ctype": "uint8_t", - "desc": "Enum `fwAutolandApproachDirection_e` Sets approach direction", - "units": "Enum", - "enum": "fwAutolandApproachDirection_e" - }, - { - "name": "landHeading1", - "ctype": "int16_t", - "desc": "Sets primary landing heading", - "units": "degrees" - }, - { - "name": "landHeading2", - "ctype": "int16_t", - "desc": "Sets secondary landing heading", - "units": "degrees" - }, - { - "name": "isSeaLevelRef", - "ctype": "uint8_t", - "desc": "Sets altitude reference", - "units": "Boolean" - } - ] + "MSP2_INAV_SET_TEMP_SENSOR_CONFIG": { + "code": 8221, + "mspv": 2, + "request": { + "payload": [ + { + "name": "type", + "ctype": "uint8_t", + "desc": "Sets sensor type (`tempSensorType_e`)", + "units": "", + "enum": "tempSensorType_e" + }, + { + "name": "address", + "ctype": "uint64_t", + "desc": "Sets sensor address/ID", + "units": "" + }, + { + "name": "alarmMin", + "ctype": "int16_t", + "desc": "Sets min alarm threshold (`tempSensorConfigMutable(index)->alarm_min`)", + "units": "0.1Β°C" + }, + { + "name": "alarmMax", + "ctype": "int16_t", + "desc": "Sets max alarm threshold (`tempSensorConfigMutable(index)->alarm_max`)", + "units": "0.1Β°C" + }, + { + "name": "osdSymbol", + "ctype": "uint8_t", + "desc": "Sets OSD symbol index (validated)", + "units": "" + }, + { + "name": "label", + "desc": "Sets sensor label (converted to uppercase)", + "ctype": "char", + "array": true, + "array_size": 4, + "array_size_define": "TEMPERATURE_LABEL_LEN", + "units": "" + } + ], + "repeating": "MAX_TEMP_SENSORS" + }, + "reply": null, + "notes": "Requires `USE_TEMPERATURE_SENSOR`. Payload must include `MAX_TEMP_SENSORS` consecutive `tempSensorConfig_t` structures (labels are uppercased).", + "description": "Sets the configuration for all onboard temperature sensors." + }, + "MSP2_INAV_TEMPERATURES": { + "code": 8222, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "temperature", + "ctype": "int16_t", + "desc": "Current temperature reading. -1000 if sensor is invalid or reading failed", + "units": "0.1Β°C" + } + ], + "repeating": "MAX_TEMP_SENSORS" + }, + "variable_len": "MAX_TEMP_SENSORS", + "notes": "Requires `USE_TEMPERATURE_SENSOR`.", + "description": "Retrieves the current readings from all configured temperature sensors." }, - "reply": null, - "notes": "Requires `USE_FW_AUTOLAND`. Expects 15 bytes. Returns error if index invalid.", - "description": "Sets the configuration for a specific Fixed Wing Autoland approach." - }, - "MSP2_INAV_GPS_UBLOX_COMMAND": { - "code": 8272, - "mspv": 2, - "request": { - "payload": [ - { - "name": "ubxCommand", - "desc": "Raw U-Blox UBX protocol command frame (including header, class, ID, length, payload, checksum)", - "ctype": "uint8_t", - "array": true, - "array_size": 0, - "units": "" - } - ] + "MSP_SIMULATOR": { + "code": 8223, + "mspv": 2, + "request": { + "payload": [ + { + "name": "simulatorVersion", + "ctype": "uint8_t", + "desc": "Version of the simulator protocol (`SIMULATOR_MSP_VERSION`)", + "units": "" + }, + { + "name": "simulatorFlags_t", + "ctype": "uint8_t", + "desc": "Bitmask: Options for HITL (`HITL_*` flags)", + "units": "Bitmask", + "bitmask": true + }, + { + "name": "gpsFixType", + "ctype": "uint8_t", + "desc": "Enum `gpsFixType_e` Type of GPS fix (If `HITL_HAS_NEW_GPS_DATA`)", + "units": "Enum", + "enum": "gpsFixType_e" + }, + { + "name": "gpsNumSat", + "ctype": "uint8_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated satellite count", + "units": "" + }, + { + "name": "gpsLat", + "ctype": "int32_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated latitude (1e7 deg)", + "units": "" + }, + { + "name": "gpsLon", + "ctype": "int32_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated longitude (1e7 deg)", + "units": "" + }, + { + "name": "gpsAlt", + "ctype": "int32_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated altitude (cm)", + "units": "" + }, + { + "name": "gpsSpeed", + "ctype": "uint16_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated ground speed (cm/s)", + "units": "" + }, + { + "name": "gpsCourse", + "ctype": "uint16_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated ground course (deci-deg)", + "units": "" + }, + { + "name": "gpsVelN", + "ctype": "int16_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated North velocity (cm/s)", + "units": "" + }, + { + "name": "gpsVelE", + "ctype": "int16_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated East velocity (cm/s)", + "units": "" + }, + { + "name": "gpsVelD", + "ctype": "int16_t", + "desc": "(If `HITL_HAS_NEW_GPS_DATA`) Simulated Down velocity (cm/s)", + "units": "" + }, + { + "name": "imuRoll", + "ctype": "int16_t", + "desc": "(If NOT `HITL_USE_IMU`) Simulated Roll (deci-deg)", + "units": "" + }, + { + "name": "imuPitch", + "ctype": "int16_t", + "desc": "(If NOT `HITL_USE_IMU`) Simulated Pitch (deci-deg)", + "units": "" + }, + { + "name": "imuYaw", + "ctype": "int16_t", + "desc": "(If NOT `HITL_USE_IMU`) Simulated Yaw (deci-deg)", + "units": "" + }, + { + "name": "accX", + "ctype": "int16_t", + "desc": "mG (G * 1000)", + "units": "" + }, + { + "name": "accY", + "ctype": "int16_t", + "desc": "mG (G * 1000)", + "units": "" + }, + { + "name": "accZ", + "ctype": "int16_t", + "desc": "mG (G * 1000)", + "units": "" + }, + { + "name": "gyroX", + "ctype": "int16_t", + "desc": "dps * 16", + "units": "" + }, + { + "name": "gyroY", + "ctype": "int16_t", + "desc": "dps * 16", + "units": "" + }, + { + "name": "gyroZ", + "ctype": "int16_t", + "desc": "dps * 16", + "units": "" + }, + { + "name": "baroPressure", + "ctype": "uint32_t", + "desc": "Pa", + "units": "" + }, + { + "name": "magX", + "ctype": "int16_t", + "desc": "Scaled", + "units": "" + }, + { + "name": "magY", + "ctype": "int16_t", + "desc": "Scaled", + "units": "" + }, + { + "name": "magZ", + "ctype": "int16_t", + "desc": "Scaled", + "units": "" + }, + { + "name": "vbat", + "ctype": "uint8_t", + "desc": "(If `HITL_EXT_BATTERY_VOLTAGE`) Simulated battery voltage (0.1V units)", + "units": "" + }, + { + "name": "airspeed", + "ctype": "uint16_t", + "desc": "(If `HITL_AIRSPEED`) Simulated airspeed (cm/s)", + "units": "" + }, + { + "name": "extFlags", + "ctype": "uint8_t", + "desc": "(If `HITL_EXTENDED_FLAGS`) Additional flags (upper 8 bits)", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "stabilizedRoll", + "ctype": "uint16_t", + "desc": "Stabilized Roll command output (-500 to 500)", + "units": "" + }, + { + "name": "stabilizedPitch", + "ctype": "uint16_t", + "desc": "Stabilized Pitch command output (-500 to 500)", + "units": "" + }, + { + "name": "stabilizedYaw", + "ctype": "uint16_t", + "desc": "Stabilized Yaw command output (-500 to 500)", + "units": "" + }, + { + "name": "stabilizedThrottle", + "ctype": "uint16_t", + "desc": "Stabilized Throttle command output (-500 to 500 if armed, else -500)", + "units": "" + }, + { + "name": "debugFlags", + "ctype": "uint8_t", + "desc": "Packed flags: Debug index (0-7), Platform type, Armed state, OSD feature status", + "units": "" + }, + { + "name": "debugValue", + "ctype": "uint32_t", + "desc": "Current debug value (`debug[simulatorData.debugIndex]`)", + "units": "" + }, + { + "name": "attitudeRoll", + "ctype": "int16_t", + "desc": "Current estimated Roll (deci-deg)", + "units": "" + }, + { + "name": "attitudePitch", + "ctype": "int16_t", + "desc": "Current estimated Pitch (deci-deg)", + "units": "" + }, + { + "name": "attitudeYaw", + "ctype": "int16_t", + "desc": "Current estimated Yaw (deci-deg)", + "units": "" + }, + { + "name": "osdHeader", + "ctype": "uint8_t", + "desc": "OSD RLE Header (255)", + "units": "", + "optional": true + }, + { + "name": "osdRows", + "ctype": "uint8_t", + "desc": "(If OSD supported) Number of OSD rows", + "units": "", + "optional": true + }, + { + "name": "osdCols", + "ctype": "uint8_t", + "desc": "(If OSD supported) Number of OSD columns", + "units": "", + "optional": true + }, + { + "name": "osdStartY", + "ctype": "uint8_t", + "desc": "(If OSD supported) Starting row for RLE data", + "units": "", + "optional": true + }, + { + "name": "osdStartX", + "ctype": "uint8_t", + "desc": "(If OSD supported) Starting column for RLE data", + "units": "", + "optional": true + }, + { + "name": "osdRleData", + "desc": "(If OSD supported) Run-length encoded OSD character data. Terminated by `[0, 0]`", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "", + "optional": true + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_SIMULATOR`. Complex message handling state changes for enabling/disabling HITL. Sensor data is injected directly. OSD data is sent using a custom RLE scheme. See `simulatorData` struct and associated code for details.", + "description": "Handles Hardware-in-the-Loop (HITL) simulation data exchange. Receives simulated sensor data and options, sends back control outputs and debug info." + }, + "MSP2_INAV_SERVO_MIXER": { + "code": 8224, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "targetChannel", + "ctype": "uint8_t", + "desc": "Servo output channel index (0-based)", + "units": "" + }, + { + "name": "inputSource", + "ctype": "uint8_t", + "desc": "Enum `inputSource_e` Input source", + "units": "", + "enum": "inputSource_e" + }, + { + "name": "rate", + "ctype": "int16_t", + "desc": "Mixing rate/weight", + "units": "" + }, + { + "name": "speed", + "ctype": "uint8_t", + "desc": "Speed/Slew rate limit (0-100)", + "units": "" + }, + { + "name": "conditionId", + "ctype": "int8_t", + "desc": "Logic Condition ID (0 to `MAX_LOGIC_CONDITIONS - 1`, or 255/-1 if none/disabled)", + "units": "" + }, + { + "name": "p2TargetChannel", + "ctype": "uint8_t", + "desc": "(Optional) Profile 2 Target channel", + "units": "", + "optional": true + }, + { + "name": "p2InputSource", + "ctype": "uint8_t", + "desc": "(Optional) Profile 2 Enum `inputSource_e` Input source", + "units": "", + "optional": true, + "enum": "inputSource_e" + }, + { + "name": "p2Rate", + "ctype": "int16_t", + "desc": "(Optional) Profile 2 Rate", + "units": "", + "optional": true + }, + { + "name": "p2Speed", + "ctype": "uint8_t", + "desc": "(Optional) Profile 2 Speed", + "units": "", + "optional": true + }, + { + "name": "p2ConditionId", + "ctype": "int8_t", + "desc": "(Optional) Profile 2 Logic Condition ID", + "units": "", + "optional": true + } + ], + "repeating": "MAX_SERVO_RULES" + }, + "variable_len": "MAX_SERVO_RULES", + "notes": "`conditionId` requires `USE_PROGRAMMING_FRAMEWORK`.", + "description": "Retrieves the custom servo mixer rules, including programming framework condition IDs, for primary and secondary mixer profiles. Supersedes `MSP_SERVO_MIX_RULES`." }, - "reply": null, - "variable_len": true, - "notes": "Requires GPS feature enabled (`FEATURE_GPS`) and the GPS driver to be U-Blox (`isGpsUblox()`). Payload must be at least 8 bytes (minimum UBX frame size). Use with extreme caution, incorrect commands can misconfigure the GPS module. Calls `gpsUbloxSendCommand()`.", - "description": "Sends a raw command directly to a U-Blox GPS module connected to the FC." - }, - "MSP2_INAV_RATE_DYNAMICS": { - "code": 8288, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "sensitivityCenter", - "ctype": "uint8_t", - "desc": "Sensitivity at stick center (`currentControlRateProfile->rateDynamics.sensitivityCenter`)", - "units": "%" - }, - { - "name": "sensitivityEnd", - "ctype": "uint8_t", - "desc": "Sensitivity at stick ends (`currentControlRateProfile->rateDynamics.sensitivityEnd`)", - "units": "%" - }, - { - "name": "correctionCenter", - "ctype": "uint8_t", - "desc": "Correction strength at stick center (`currentControlRateProfile->rateDynamics.correctionCenter`)", - "units": "%" - }, - { - "name": "correctionEnd", - "ctype": "uint8_t", - "desc": "Correction strength at stick ends (`currentControlRateProfile->rateDynamics.correctionEnd`)", - "units": "%" - }, - { - "name": "weightCenter", - "ctype": "uint8_t", - "desc": "Transition weight at stick center (`currentControlRateProfile->rateDynamics.weightCenter`)", - "units": "%" - }, - { - "name": "weightEnd", - "ctype": "uint8_t", - "desc": "Transition weight at stick ends (`currentControlRateProfile->rateDynamics.weightEnd`)", - "units": "%" - } - ] + "MSP2_INAV_SET_SERVO_MIXER": { + "code": 8225, + "mspv": 2, + "request": { + "payload": [ + { + "name": "ruleIndex", + "ctype": "uint8_t", + "desc": "Index of the rule to set (0 to `MAX_SERVO_RULES - 1`)", + "units": "" + }, + { + "name": "targetChannel", + "ctype": "uint8_t", + "desc": "Servo output channel index", + "units": "" + }, + { + "name": "inputSource", + "ctype": "uint8_t", + "desc": "Enum `inputSource_e` Input source", + "units": "", + "enum": "inputSource_e" + }, + { + "name": "rate", + "ctype": "int16_t", + "desc": "Mixing rate/weight", + "units": "" + }, + { + "name": "speed", + "ctype": "uint8_t", + "desc": "Speed/Slew rate limit (0-100)", + "units": "" + }, + { + "name": "conditionId", + "ctype": "int8_t", + "desc": "Logic Condition ID (255/-1 if none). Ignored if `USE_PROGRAMMING_FRAMEWORK` is disabled", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 7 bytes. Returns error if index invalid. Calls `loadCustomServoMixer()`.", + "description": "Sets a single custom servo mixer rule, including programming framework condition ID. Supersedes `MSP_SET_SERVO_MIX_RULE`." + }, + "MSP2_INAV_LOGIC_CONDITIONS": { + "code": 8226, + "mspv": 2, + "not_implemented": true, + "request": null, + "reply": { + "payload": [ + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 if the condition is enabled", + "units": "" + }, + { + "name": "activatorId", + "ctype": "int8_t", + "desc": "Activator condition ID (-1/255 if none)", + "units": "" + }, + { + "name": "operation", + "ctype": "uint8_t", + "desc": "Enum `logicOperation_e` Logical operation (AND, OR, XOR, etc.)", + "units": "", + "enum": "logicOperation_e" + }, + { + "name": "operandAType", + "ctype": "uint8_t", + "desc": "Enum `logicOperandType_e` Type of the first operand (Flight Mode, GVAR, etc.)", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "operandAValue", + "ctype": "int32_t", + "desc": "Value/ID of the first operand", + "units": "" + }, + { + "name": "operandBType", + "ctype": "uint8_t", + "desc": "Enum `logicOperandType_e`: Type of the second operand", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "operandBValue", + "ctype": "int32_t", + "desc": "Value/ID of the second operand", + "units": "" + }, + { + "name": "flags", + "ctype": "uint8_t", + "desc": "Bitmask: Condition flags (`logicConditionFlags_e`)", + "units": "Bitmask", + "bitmask": true + } + ], + "repeating": "MAX_LOGIC_CONDITIONS" + }, + "variable_len": "MAX_LOGIC_CONDITIONS", + "notes": "Deprecated, causes buffer overflow for 14*64 bytes", + "description": "Retrieves the configuration of all defined Logic Conditions. Requires `USE_PROGRAMMING_FRAMEWORK`. See `logicCondition_t` structure." }, - "notes": "Requires `USE_RATE_DYNAMICS`.", - "description": "Retrieves Rate Dynamics configuration parameters for the current control rate profile." - }, - "MSP2_INAV_SET_RATE_DYNAMICS": { - "code": 8289, - "mspv": 2, - "request": { - "payload": [ - { - "name": "sensitivityCenter", - "ctype": "uint8_t", - "desc": "Sets sensitivity at center", - "units": "%" - }, - { - "name": "sensitivityEnd", - "ctype": "uint8_t", - "desc": "Sets sensitivity at ends", - "units": "%" - }, - { - "name": "correctionCenter", - "ctype": "uint8_t", - "desc": "Sets correction at center", - "units": "%" - }, - { - "name": "correctionEnd", - "ctype": "uint8_t", - "desc": "Sets correction at ends", - "units": "%" - }, - { - "name": "weightCenter", - "ctype": "uint8_t", - "desc": "Sets weight at center", - "units": "%" - }, - { - "name": "weightEnd", - "ctype": "uint8_t", - "desc": "Sets weight at ends", - "units": "%" - } - ] + "MSP2_INAV_SET_LOGIC_CONDITIONS": { + "code": 8227, + "mspv": 2, + "request": { + "payload": [ + { + "name": "conditionIndex", + "ctype": "uint8_t", + "desc": "Index of the condition to set (0 to `MAX_LOGIC_CONDITIONS - 1`)", + "units": "" + }, + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 to enable the condition", + "units": "" + }, + { + "name": "activatorId", + "ctype": "int8_t", + "desc": "Activator condition ID (-1/255 if none)", + "units": "" + }, + { + "name": "operation", + "ctype": "uint8_t", + "desc": "Enum `logicOperation_e` Logical operation", + "units": "", + "enum": "logicOperation_e" + }, + { + "name": "operandAType", + "ctype": "uint8_t", + "desc": "Enum `logicOperandType_e` Type of operand A", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "operandAValue", + "ctype": "int32_t", + "desc": "Value/ID of operand A", + "units": "" + }, + { + "name": "operandBType", + "ctype": "uint8_t", + "desc": "Enum `logicOperandType_e` Type of operand B", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "operandBValue", + "ctype": "int32_t", + "desc": "Value/ID of operand B", + "units": "" + }, + { + "name": "flags", + "ctype": "uint8_t", + "desc": "Bitmask: Condition flags (`logicConditionFlags_e`)", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "reply": null, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 15 bytes. Returns error if index is invalid.", + "description": "Sets the configuration for a single Logic Condition by its index." + }, + "MSP2_INAV_GLOBAL_FUNCTIONS": { + "code": 8228, + "mspv": 2, + "not_implemented": true + }, + "MSP2_INAV_SET_GLOBAL_FUNCTIONS": { + "code": 8229, + "mspv": 2, + "not_implemented": true + }, + "MSP2_INAV_LOGIC_CONDITIONS_STATUS": { + "code": 8230, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "conditionValues", + "ctype": "int32_t", + "desc": "Array of current values for each logic condition (`logicConditionGetValue(i)`). 1 for true, 0 for false, or numerical value depending on operation", + "array": true, + "array_size": 64, + "array_size_define": "MAX_LOGIC_CONDITIONS", + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", + "description": "Retrieves the current evaluated status (true/false or numerical value) of all logic conditions." + }, + "MSP2_INAV_GVAR_STATUS": { + "code": 8231, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "gvarValues", + "desc": "Array of current values for each global variable (`gvGet(i)`)", + "ctype": "int32_t", + "array": true, + "array_size": 8, + "array_size_define": "MAX_GLOBAL_VARIABLES", + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", + "description": "Retrieves the current values of all Global Variables (GVARS)." + }, + "MSP2_INAV_PROGRAMMING_PID": { + "code": 8232, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 if the PID is enabled", + "units": "" + }, + { + "name": "setpointType", + "ctype": "uint8_t", + "desc": "Enum (`logicOperandType_e`) Type of the setpoint source", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "setpointValue", + "ctype": "int32_t", + "desc": "Value/ID of the setpoint source", + "units": "" + }, + { + "name": "measurementType", + "ctype": "uint8_t", + "desc": "Enum (`logicOperandType_e`) Type of the measurement source", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "measurementValue", + "ctype": "int32_t", + "desc": "Value/ID of the measurement source", + "units": "" + }, + { + "name": "gainP", + "ctype": "uint16_t", + "desc": "Proportional gain", + "units": "" + }, + { + "name": "gainI", + "ctype": "uint16_t", + "desc": "Integral gain", + "units": "" + }, + { + "name": "gainD", + "ctype": "uint16_t", + "desc": "Derivative gain", + "units": "" + }, + { + "name": "gainFF", + "ctype": "uint16_t", + "desc": "Feed-forward gain", + "units": "" + } + ], + "repeating": "MAX_PROGRAMMING_PID_COUNT" + }, + "variable_len": "MAX_PROGRAMMING_PID_COUNT", + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. See `programmingPid_t` structure.", + "description": "Retrieves the configuration of all Programming PIDs." }, - "reply": null, - "notes": "Requires `USE_RATE_DYNAMICS`. Expects 6 bytes.", - "description": "Sets Rate Dynamics configuration parameters for the current control rate profile." - }, - "MSP2_INAV_EZ_TUNE": { - "code": 8304, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Boolean: 1 if EZ-Tune is enabled (`ezTune()->enabled`)", - "units": "" - }, - { - "name": "filterHz", - "ctype": "uint16_t", - "desc": "Filter frequency used during tuning (`ezTune()->filterHz`)", - "units": "" - }, - { - "name": "axisRatio", - "ctype": "uint8_t", - "desc": "Roll vs Pitch axis tuning ratio (`ezTune()->axisRatio`)", - "units": "" - }, - { - "name": "response", - "ctype": "uint8_t", - "desc": "Desired response characteristic (`ezTune()->response`)", - "units": "" - }, - { - "name": "damping", - "ctype": "uint8_t", - "desc": "Desired damping characteristic (`ezTune()->damping`)", - "units": "" - }, - { - "name": "stability", - "ctype": "uint8_t", - "desc": "Stability preference (`ezTune()->stability`)", - "units": "" - }, - { - "name": "aggressiveness", - "ctype": "uint8_t", - "desc": "Aggressiveness preference (`ezTune()->aggressiveness`)", - "units": "" - }, - { - "name": "rate", - "ctype": "uint8_t", - "desc": "Resulting rate setting (`ezTune()->rate`)", - "units": "" - }, - { - "name": "expo", - "ctype": "uint8_t", - "desc": "Resulting expo setting (`ezTune()->expo`)", - "units": "" - }, - { - "name": "snappiness", - "ctype": "uint8_t", - "desc": "Snappiness preference (`ezTune()->snappiness`)", - "units": "" - } - ] + "MSP2_INAV_SET_PROGRAMMING_PID": { + "code": 8233, + "mspv": 2, + "request": { + "payload": [ + { + "name": "pidIndex", + "ctype": "uint8_t", + "desc": "Index of the Programming PID to set (0 to `MAX_PROGRAMMING_PID_COUNT - 1`)", + "units": "" + }, + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 to enable the PID", + "units": "" + }, + { + "name": "setpointType", + "ctype": "uint8_t", + "desc": "Enum (`logicOperandType_e`) Type of the setpoint source", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "setpointValue", + "ctype": "int32_t", + "desc": "Value/ID of the setpoint source", + "units": "" + }, + { + "name": "measurementType", + "ctype": "uint8_t", + "desc": "Enum (`logicOperandType_e`) Type of the measurement source", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "measurementValue", + "ctype": "int32_t", + "desc": "Value/ID of the measurement source", + "units": "" + }, + { + "name": "gainP", + "ctype": "uint16_t", + "desc": "Proportional gain", + "units": "" + }, + { + "name": "gainI", + "ctype": "uint16_t", + "desc": "Integral gain", + "units": "" + }, + { + "name": "gainD", + "ctype": "uint16_t", + "desc": "Derivative gain", + "units": "" + }, + { + "name": "gainFF", + "ctype": "uint16_t", + "desc": "Feed-forward gain", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Expects 20 bytes. Returns error if index is invalid.", + "description": "Sets the configuration for a single Programming PID by its index." + }, + "MSP2_INAV_PROGRAMMING_PID_STATUS": { + "code": 8234, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "pidOutputs", + "desc": "Array of current output values for each Programming PID (`programmingPidGetOutput(i)`, signed)", + "array": true, + "ctype": "int32_t", + "array_size": 4, + "array_size_define": "MAX_PROGRAMMING_PID_COUNT", + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", + "description": "Retrieves the current output value of all Programming PIDs." + }, + "MSP2_PID": { + "code": 8240, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "P", + "ctype": "uint8_t", + "desc": "Proportional gain (`pidBank()->pid[i].P`), constrained 0-255", + "units": "" + }, + { + "name": "I", + "ctype": "uint8_t", + "desc": "Integral gain (`pidBank()->pid[i].I`), constrained 0-255", + "units": "" + }, + { + "name": "D", + "ctype": "uint8_t", + "desc": "Derivative gain (`pidBank()->pid[i].D`), constrained 0-255", + "units": "" + }, + { + "name": "FF", + "ctype": "uint8_t", + "desc": "Feed-forward gain (`pidBank()->pid[i].FF`), constrained 0-255", + "units": "" + } + ], + "repeating": "PID_ITEM_COUNT" + }, + "variable_len": "PID_ITEM_COUNT", + "notes": "`PID_ITEM_COUNT` defines the number of standard PID controllers (Roll, Pitch, Yaw, Alt, Vel, etc.). Updates from EZ-Tune if enabled.", + "description": "Retrieves the standard PID controller gains (P, I, D, FF) for the current PID profile." }, - "notes": "Requires `USE_EZ_TUNE`. Calls `ezTuneUpdate()` before sending.", - "description": "Retrieves the current EZ-Tune parameters." - }, - "MSP2_INAV_EZ_TUNE_SET": { - "code": 8305, - "mspv": 2, - "request": { - "payload": [ - { - "name": "enabled", - "ctype": "uint8_t", - "desc": "Sets enabled state", - "units": "" - }, - { - "name": "filterHz", - "ctype": "uint16_t", - "desc": "Sets filter frequency", - "units": "" - }, - { - "name": "axisRatio", - "ctype": "uint8_t", - "desc": "Sets axis ratio", - "units": "" - }, - { - "name": "response", - "ctype": "uint8_t", - "desc": "Sets response characteristic", - "units": "" - }, - { - "name": "damping", - "ctype": "uint8_t", - "desc": "Sets damping characteristic", - "units": "" - }, - { - "name": "stability", - "ctype": "uint8_t", - "desc": "Sets stability preference", - "units": "" - }, - { - "name": "aggressiveness", - "ctype": "uint8_t", - "desc": "Sets aggressiveness preference", - "units": "" - }, - { - "name": "rate", - "ctype": "uint8_t", - "desc": "Sets rate setting", - "units": "" - }, - { - "name": "expo", - "ctype": "uint8_t", - "desc": "Sets expo setting", - "units": "" - }, - { - "name": "snappiness", - "ctype": "uint8_t", - "desc": "(Optional) Sets snappiness preference", - "units": "", - "optional": true - } - ] + "MSP2_SET_PID": { + "code": 8241, + "mspv": 2, + "request": { + "payload": [ + { + "name": "P", + "ctype": "uint8_t", + "desc": "Sets Proportional gain (`pidBankMutable()->pid[i].P`)", + "units": "" + }, + { + "name": "I", + "ctype": "uint8_t", + "desc": "Sets Integral gain (`pidBankMutable()->pid[i].I`)", + "units": "" + }, + { + "name": "D", + "ctype": "uint8_t", + "desc": "Sets Derivative gain (`pidBankMutable()->pid[i].D`)", + "units": "" + }, + { + "name": "FF", + "ctype": "uint8_t", + "desc": "Sets Feed-forward gain (`pidBankMutable()->pid[i].FF`)", + "units": "" + } + ], + "repeating": "PID_ITEM_COUNT" + }, + "reply": null, + "variable_len": "PID_ITEM_COUNT", + "notes": "Expects `PID_ITEM_COUNT * 4` bytes. Calls `schedulePidGainsUpdate()` and `navigationUsePIDs()`.", + "description": "Sets the standard PID controller gains (P, I, D, FF) for the current PID profile." + }, + "MSP2_INAV_OPFLOW_CALIBRATION": { + "code": 8242, + "mspv": 2, + "request": null, + "reply": null, + "notes": "Requires `USE_OPFLOW`. Will fail if armed. Calls `opflowStartCalibration()`.", + "description": "Starts the optical flow sensor calibration procedure." + }, + "MSP2_INAV_FWUPDT_PREPARE": { + "code": 8243, + "mspv": 2, + "request": { + "payload": [ + { + "name": "firmwareSize", + "ctype": "uint32_t", + "desc": "Total size of the incoming firmware file in bytes", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `MSP_FIRMWARE_UPDATE`. Expects 4 bytes. Returns error if preparation fails (e.g., no storage, invalid size). Calls `firmwareUpdatePrepare()`.", + "description": "Prepares the flight controller to receive a firmware update via MSP." }, - "reply": null, - "notes": "Requires `USE_EZ_TUNE`. Expects 10 or 11 bytes. Calls `ezTuneUpdate()` after setting parameters.", - "description": "Sets the EZ-Tune parameters and triggers an update." - }, - "MSP2_INAV_SELECT_MIXER_PROFILE": { - "code": 8320, - "mspv": 2, - "request": { - "payload": [ - { - "name": "mixerProfileIndex", - "ctype": "uint8_t", - "desc": "Index of the mixer profile to activate (0-based)", - "units": "" - } - ] + "MSP2_INAV_FWUPDT_STORE": { + "code": 8244, + "mspv": 2, + "request": { + "payload": [ + { + "name": "firmwareChunk", + "desc": "Chunk of firmware data", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "reply": null, + "variable_len": true, + "notes": "Requires `MSP_FIRMWARE_UPDATE`. Returns error if storage fails (e.g., out of space, checksum error). Called repeatedly until the entire firmware is transferred. Calls `firmwareUpdateStore()`.", + "description": "Stores a chunk of firmware data received via MSP." + }, + "MSP2_INAV_FWUPDT_EXEC": { + "code": 8245, + "mspv": 2, + "request": { + "payload": [ + { + "name": "updateType", + "ctype": "uint8_t", + "desc": "Type of update (e.g., full flash, specific section - currently ignored/unused)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `MSP_FIRMWARE_UPDATE`. Expects 1 byte. Returns error if update cannot start (e.g., not fully received). Calls `firmwareUpdateExec()`. If successful, the device will reboot into the new firmware.", + "description": "Executes the firmware update process (flashes the stored firmware and reboots)." + }, + "MSP2_INAV_FWUPDT_ROLLBACK_PREPARE": { + "code": 8246, + "mspv": 2, + "request": null, + "reply": null, + "notes": "Requires `MSP_FIRMWARE_UPDATE`. Returns error if rollback preparation fails (e.g., no rollback image available). Calls `firmwareUpdateRollbackPrepare()`.", + "description": "Prepares the flight controller to perform a firmware rollback to the previously stored version." + }, + "MSP2_INAV_FWUPDT_ROLLBACK_EXEC": { + "code": 8247, + "mspv": 2, + "request": null, + "reply": null, + "notes": "Requires `MSP_FIRMWARE_UPDATE`. Returns error if rollback cannot start. Calls `firmwareUpdateRollbackExec()`. If successful, the device will reboot into the backup firmware.", + "description": "Executes the firmware rollback process (flashes the stored backup firmware and reboots)." + }, + "MSP2_INAV_SAFEHOME": { + "code": 8248, + "mspv": 2, + "request": { + "payload": [ + { + "name": "safehomeIndex", + "ctype": "uint8_t", + "desc": "Index of the safe home location (0 to `MAX_SAFE_HOMES - 1`)", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "safehomeIndex", + "ctype": "uint8_t", + "desc": "Index requested", + "units": "" + }, + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 if this safe home is enabled", + "units": "" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude (1e7 deg)", + "units": "" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude (1e7 deg)", + "units": "" + } + ] + }, + "notes": "Requires `USE_SAFE_HOME`. Used by `mspFcSafeHomeOutCommand`. See `MSP2_INAV_SET_SAFEHOME` for setting.", + "description": "Get or Set configuration for a specific Safe Home location." }, - "reply": null, - "notes": "Expects 1 byte. Will fail if armed. Calls `setConfigMixerProfileAndWriteEEPROM()`. Only applicable if `MAX_MIXER_PROFILE_COUNT` > 1.", - "description": "Selects the active mixer profile and saves configuration." - }, - "MSP2_ADSB_VEHICLE_LIST": { - "code": 8336, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "maxVehicles", - "ctype": "uint8_t", - "desc": "Maximum number of vehicles tracked (`MAX_ADSB_VEHICLES`). 0 if `USE_ADSB` disabled", - "units": "" - }, - { - "name": "callsignLength", - "ctype": "uint8_t", - "desc": "Maximum length of callsign string (`ADSB_CALL_SIGN_MAX_LENGTH`). 0 if `USE_ADSB` disabled", - "units": "" - }, - { - "name": "totalVehicleMsgs", - "ctype": "uint32_t", - "desc": "Total vehicle messages received (`getAdsbStatus()->vehiclesMessagesTotal`). 0 if `USE_ADSB` disabled", - "units": "" - }, - { - "name": "totalHeartbeatMsgs", - "ctype": "uint32_t", - "desc": "Total heartbeat messages received (`getAdsbStatus()->heartbeatMessagesTotal`). 0 if `USE_ADSB` disabled", - "units": "" - }, - { - "repeating": "maxVehicles", - "payload": [ - { - "name": "callsign", - "desc": "Fixed-length callsign from `adsbVehicle->vehicleValues.callsign` (padded with NULs if shorter).", - "ctype": "char", - "array": true, - "array_size": 9, - "array_size_define": "ADSB_CALL_SIGN_MAX_LENGTH", - "units": "" - }, - { - "name": "icao", - "ctype": "uint32_t", - "desc": "ICAO address (`adsbVehicle->vehicleValues.icao`).", - "units": "" - }, - { - "name": "lat", - "ctype": "int32_t", - "desc": "Latitude in degrees * 1e7 (`adsbVehicle->vehicleValues.lat`).", - "units": "1e-7 deg" - }, - { - "name": "lon", - "ctype": "int32_t", - "desc": "Longitude in degrees * 1e7 (`adsbVehicle->vehicleValues.lon`).", - "units": "1e-7 deg" - }, - { - "name": "alt", - "ctype": "int32_t", - "desc": "Altitude above sea level (`adsbVehicle->vehicleValues.alt`).", - "units": "cm" - }, - { - "name": "headingDeg", - "ctype": "uint16_t", - "desc": "Course over ground in whole degrees (`CENTIDEGREES_TO_DEGREES(vehicleValues.heading)`).", - "units": "deg" - }, - { - "name": "tslc", - "ctype": "uint8_t", - "desc": "Time since last communication (`adsbVehicle->vehicleValues.tslc`).", - "units": "s" - }, - { - "name": "emitterType", - "ctype": "uint8_t", - "desc": "Emitter category (`adsbVehicle->vehicleValues.emitterType`) (refers to enum 'ADSB_EMITTER_TYPE', but none found)", - "units": "" - }, - { - "name": "ttl", - "ctype": "uint8_t", - "desc": "TTL counter used for list maintenance (`adsbVehicle->ttl`).", - "units": "" - } - ] - } - ] + "MSP2_INAV_SET_SAFEHOME": { + "code": 8249, + "mspv": 2, + "request": { + "payload": [ + { + "name": "safehomeIndex", + "ctype": "uint8_t", + "desc": "Index of the safe home location (0 to `MAX_SAFE_HOMES - 1`)", + "units": "" + }, + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 to enable this safe home", + "units": "" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Latitude (1e7 deg)", + "units": "" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Longitude (1e7 deg)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_SAFE_HOME`. Expects 10 bytes. Returns error if index invalid. Resets corresponding FW autoland approach if `USE_FW_AUTOLAND` is enabled.", + "description": "Sets the configuration for a specific Safe Home location." + }, + "MSP2_INAV_MISC2": { + "code": 8250, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "uptimeSeconds", + "ctype": "uint32_t", + "desc": "Time since boot (`micros() / 1000000`)", + "units": "Seconds" + }, + { + "name": "flightTimeSeconds", + "ctype": "uint32_t", + "desc": "Accumulated flight time (`getFlightTime()`)", + "units": "Seconds" + }, + { + "name": "throttlePercent", + "ctype": "uint8_t", + "desc": "Current throttle output percentage (`getThrottlePercent(true)`)", + "units": "%" + }, + { + "name": "autoThrottleFlag", + "ctype": "uint8_t", + "desc": "1 if navigation is controlling throttle, 0 otherwise (`navigationIsControllingThrottle()`)", + "units": "Boolean" + } + ] + }, + "notes": "", + "description": "Retrieves miscellaneous runtime information including timers and throttle status." }, - "variable_len": "maxVehicles", - "notes": "Requires `USE_ADSB`. Only a subset of `adsbVehicle_t` is transmitted (callsign, core values, heading in whole degrees, TSLC, emitter type, TTL).", - "description": "Retrieves the list of currently tracked ADSB (Automatic Dependent Surveillance–Broadcast) vehicles. See `adsbVehicle_t` and `adsbVehicleValues_t` in `io/adsb.h` for the exact structure fields." - }, - "MSP2_INAV_CUSTOM_OSD_ELEMENTS": { - "code": 8448, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "maxElements", - "ctype": "uint8_t", - "desc": "Maximum number of custom elements (`MAX_CUSTOM_ELEMENTS`)", - "units": "" - }, - { - "name": "maxTextLength", - "ctype": "uint8_t", - "desc": "Maximum length of the text part (`OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1`)", - "units": "" - }, - { - "name": "maxParts", - "ctype": "uint8_t", - "desc": "Maximum number of parts per element (`CUSTOM_ELEMENTS_PARTS`)", - "units": "" - } - ] + "MSP2_INAV_LOGIC_CONDITIONS_SINGLE": { + "code": 8251, + "mspv": 2, + "request": { + "payload": [ + { + "name": "conditionIndex", + "ctype": "uint8_t", + "desc": "Index of the condition to retrieve (0 to `MAX_LOGIC_CONDITIONS - 1`)", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 if enabled", + "units": "" + }, + { + "name": "activatorId", + "ctype": "int8_t", + "desc": "Activator ID (-1/255 if none)", + "units": "" + }, + { + "name": "operation", + "ctype": "uint8_t", + "desc": "Enum `logicOperation_e` Logical operation", + "units": "", + "enum": "logicOperation_e" + }, + { + "name": "operandAType", + "ctype": "uint8_t", + "desc": "Enum `logicOperandType_e` Type of operand A", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "operandAValue", + "ctype": "int32_t", + "desc": "Value/ID of operand A", + "units": "" + }, + { + "name": "operandBType", + "ctype": "uint8_t", + "desc": "Enum `logicOperandType_e` Type of operand B", + "units": "", + "enum": "logicOperandType_e" + }, + { + "name": "operandBValue", + "ctype": "int32_t", + "desc": "Value/ID of operand B", + "units": "" + }, + { + "name": "flags", + "ctype": "uint8_t", + "desc": "Bitmask: Condition flags (`logicConditionFlags_e`)", + "units": "Bitmask", + "bitmask": true + } + ] + }, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`. Used by `mspFcLogicConditionCommand`.", + "description": "Gets the configuration for a single Logic Condition by its index." + }, + "MSP2_INAV_ESC_RPM": { + "code": 8256, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "escRpm", + "ctype": "uint32_t", + "desc": "RPM reported by the ESC", + "units": "RPM" + } + ], + "repeating": "getMotorCount()" + }, + "variable_len": "getMotorCount()", + "notes": "Requires `USE_ESC_SENSOR`. Payload size depends on the number of detected motors with telemetry.", + "description": "Retrieves the RPM reported by each ESC via telemetry." + }, + "MSP2_INAV_ESC_TELEM": { + "code": 8257, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "motorCount", + "ctype": "uint8_t", + "desc": "Number of motors reporting telemetry (`getMotorCount()`)", + "units": "" + }, + { + "name": "escData", + "desc": "Array of `escSensorData_t` structures containing voltage, current, temp, RPM, errors etc. for each ESC", + "ctype": "escSensorData_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_ESC_SENSOR`. See `escSensorData_t` in `sensors/esc_sensor.h` for the exact structure fields.", + "description": "Retrieves the full telemetry data structure reported by each ESC." + }, + "MSP2_INAV_LED_STRIP_CONFIG_EX": { + "code": 8264, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "ledConfig", + "ctype": "ledConfig_t", + "desc": "Raw `ledConfig_t` structure (6 bytes) holding position, function, overlay, color, direction, and params bitfields (`io/ledstrip.h`).", + "units": "" + } + ], + "repeating": "LED_MAX_STRIP_LENGTH" + }, + "variable_len": "LED_MAX_STRIP_LENGTH", + "notes": "Requires `USE_LED_STRIP`. See `ledConfig_t` in `io/ledstrip.h` for structure fields (position, function, overlay, color, direction, params).", + "description": "Retrieves the full configuration for each LED on the strip using the `ledConfig_t` structure. Supersedes `MSP_LED_STRIP_CONFIG`." }, - "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", - "description": "Retrieves counts related to custom OSD elements defined by the programming framework." - }, - "MSP2_INAV_CUSTOM_OSD_ELEMENT": { - "code": 8449, - "mspv": 2, - "request": { - "payload": [ - { - "name": "elementIndex", - "ctype": "uint8_t", - "desc": "Index of the custom element (0 to `MAX_CUSTOM_ELEMENTS - 1`)" - } - ] + "MSP2_INAV_SET_LED_STRIP_CONFIG_EX": { + "code": 8265, + "mspv": 2, + "request": { + "payload": [ + { + "name": "ledIndex", + "ctype": "uint8_t", + "desc": "Index of the LED to configure (0 to `LED_MAX_STRIP_LENGTH - 1`)", + "units": "" + }, + { + "name": "ledConfig", + "ctype": "ledConfig_t", + "desc": "Raw `ledConfig_t` structure (6 bytes) mirroring the firmware layout.", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_LED_STRIP`. Expects `1 + sizeof(ledConfig_t)` bytes. Returns error if index invalid. Calls `reevaluateLedConfig()`.", + "description": "Sets the configuration for a single LED on the strip using the `ledConfig_t` structure. Supersedes `MSP_SET_LED_STRIP_CONFIG`." + }, + "MSP2_INAV_FW_APPROACH": { + "code": 8266, + "mspv": 2, + "request": { + "payload": [ + { + "name": "approachIndex", + "ctype": "uint8_t", + "desc": "Index of the approach setting (0 to `MAX_FW_LAND_APPOACH_SETTINGS - 1`)", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "approachIndex", + "ctype": "uint8_t", + "desc": "Index requested", + "units": "Index" + }, + { + "name": "approachAlt", + "ctype": "int32_t", + "desc": "Signed altitude for the approach phase (`navFwAutolandApproach_t.approachAlt`)", + "units": "cm" + }, + { + "name": "landAlt", + "ctype": "int32_t", + "desc": "Signed altitude for the final landing phase (`navFwAutolandApproach_t.landAlt`)", + "units": "cm" + }, + { + "name": "approachDirection", + "ctype": "uint8_t", + "desc": "Enum `fwAutolandApproachDirection_e`: Direction of approach (From WP, Specific Heading)", + "units": "Enum", + "enum": "fwAutolandApproachDirection_e" + }, + { + "name": "landHeading1", + "ctype": "int16_t", + "desc": "Primary landing heading (if approachDirection requires it)", + "units": "degrees" + }, + { + "name": "landHeading2", + "ctype": "int16_t", + "desc": "Secondary landing heading (if approachDirection requires it)", + "units": "degrees" + }, + { + "name": "isSeaLevelRef", + "ctype": "uint8_t", + "desc": "1 if altitudes are relative to sea level, 0 if relative to home", + "units": "Boolean" + } + ] + }, + "notes": "Requires `USE_FW_AUTOLAND`. Used by `mspFwApproachOutCommand`. See `MSP2_INAV_SET_FW_APPROACH` for setting.", + "description": "Get or Set configuration for a specific Fixed Wing Autoland approach." }, - "reply": { - "payload": [ - { - "repeating": "CUSTOM_ELEMENTS_PARTS", - "payload": [ - { - "name": "partType", - "ctype": "uint8_t", - "enum": "osdCustomElementType_e", - "desc": "Type of this part" - }, - { - "name": "partValue", - "ctype": "uint16_t", - "desc": "Value/ID associated with this part" - } - ] - }, - { - "name": "visibilityType", - "ctype": "uint8_t", - "enum": "osdCustomElementTypeVisibility_e", - "desc": "Visibility condition source" - }, - { - "name": "visibilityValue", - "ctype": "uint16_t", - "desc": "Value/ID of the visibility condition source" - }, - { - "name": "elementText", - "desc": "Static text bytes", - "ctype": "char", - "array": true, - "array_size": 0, - "array_size_define": "OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1" - } - ] + "MSP2_INAV_SET_FW_APPROACH": { + "code": 8267, + "mspv": 2, + "request": { + "payload": [ + { + "name": "approachIndex", + "ctype": "uint8_t", + "desc": "Index of the approach setting (0 to `MAX_FW_LAND_APPOACH_SETTINGS - 1`)", + "units": "Index" + }, + { + "name": "approachAlt", + "ctype": "int32_t", + "desc": "Signed approach altitude (`navFwAutolandApproach_t.approachAlt`)", + "units": "cm" + }, + { + "name": "landAlt", + "ctype": "int32_t", + "desc": "Signed landing altitude (`navFwAutolandApproach_t.landAlt`)", + "units": "cm" + }, + { + "name": "approachDirection", + "ctype": "uint8_t", + "desc": "Enum `fwAutolandApproachDirection_e` Sets approach direction", + "units": "Enum", + "enum": "fwAutolandApproachDirection_e" + }, + { + "name": "landHeading1", + "ctype": "int16_t", + "desc": "Sets primary landing heading", + "units": "degrees" + }, + { + "name": "landHeading2", + "ctype": "int16_t", + "desc": "Sets secondary landing heading", + "units": "degrees" + }, + { + "name": "isSeaLevelRef", + "ctype": "uint8_t", + "desc": "Sets altitude reference", + "units": "Boolean" + } + ] + }, + "reply": null, + "notes": "Requires `USE_FW_AUTOLAND`. Expects 15 bytes. Returns error if index invalid.", + "description": "Sets the configuration for a specific Fixed Wing Autoland approach." }, - "notes": "Reply emitted only if idx < MAX_CUSTOM_ELEMENTS; otherwise no body is written.", - "description": "Gets the configuration of a single custom OSD element defined by the programming framework." - }, - "MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS": { - "code": 8450, - "mspv": 2, - "request": { - "payload": [ - { - "name": "elementIndex", - "ctype": "uint8_t", - "desc": "Index of the custom element (0 to `MAX_CUSTOM_ELEMENTS - 1`)" - }, - { - "repeating": "CUSTOM_ELEMENTS_PARTS", - "payload": [ - { - "name": "partType", - "ctype": "uint8_t", - "enum": "osdCustomElementType_e", - "desc": "Type of this part" - }, - { - "name": "partValue", - "ctype": "uint16_t", - "desc": "Value/ID associated with this part" - } - ] - }, - { - "name": "visibilityType", - "ctype": "uint8_t", - "enum": "osdCustomElementTypeVisibility_e", - "desc": "Visibility condition source" - }, - { - "name": "visibilityValue", - "ctype": "uint16_t", - "desc": "Value/ID of the visibility condition source" - }, - { - "name": "elementText", - "desc": "Raw bytes", - "ctype": "char", - "array": true, - "array_size": 0, - "array_size_define": "OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1" - } - ] + "MSP2_INAV_GPS_UBLOX_COMMAND": { + "code": 8272, + "mspv": 2, + "request": { + "payload": [ + { + "name": "ubxCommand", + "desc": "Raw U-Blox UBX protocol command frame (including header, class, ID, length, payload, checksum)", + "ctype": "uint8_t", + "array": true, + "array_size": 0, + "units": "" + } + ] + }, + "reply": null, + "variable_len": true, + "notes": "Requires GPS feature enabled (`FEATURE_GPS`) and the GPS driver to be U-Blox (`isGpsUblox()`). Payload must be at least 8 bytes (minimum UBX frame size). Use with extreme caution, incorrect commands can misconfigure the GPS module. Calls `gpsUbloxSendCommand()`.", + "description": "Sends a raw command directly to a U-Blox GPS module connected to the FC." + }, + "MSP2_INAV_RATE_DYNAMICS": { + "code": 8288, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "sensitivityCenter", + "ctype": "uint8_t", + "desc": "Sensitivity at stick center (`currentControlRateProfile->rateDynamics.sensitivityCenter`)", + "units": "%" + }, + { + "name": "sensitivityEnd", + "ctype": "uint8_t", + "desc": "Sensitivity at stick ends (`currentControlRateProfile->rateDynamics.sensitivityEnd`)", + "units": "%" + }, + { + "name": "correctionCenter", + "ctype": "uint8_t", + "desc": "Correction strength at stick center (`currentControlRateProfile->rateDynamics.correctionCenter`)", + "units": "%" + }, + { + "name": "correctionEnd", + "ctype": "uint8_t", + "desc": "Correction strength at stick ends (`currentControlRateProfile->rateDynamics.correctionEnd`)", + "units": "%" + }, + { + "name": "weightCenter", + "ctype": "uint8_t", + "desc": "Transition weight at stick center (`currentControlRateProfile->rateDynamics.weightCenter`)", + "units": "%" + }, + { + "name": "weightEnd", + "ctype": "uint8_t", + "desc": "Transition weight at stick ends (`currentControlRateProfile->rateDynamics.weightEnd`)", + "units": "%" + } + ] + }, + "notes": "Requires `USE_RATE_DYNAMICS`.", + "description": "Retrieves Rate Dynamics configuration parameters for the current control rate profile." }, - "reply": null, - "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.", - "description": "Sets the configuration of one custom OSD element." - }, - "MSP2_INAV_OUTPUT_MAPPING_EXT2": { - "code": 8461, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "timerId", - "ctype": "uint8_t", - "desc": "Hardware timer identifier (e.g., `TIM1`, `TIM2`). SITL uses index", - "units": "" - }, - { - "name": "usageFlags", - "ctype": "uint32_t", - "desc": "Full 32-bit timer usage flags (`TIM_USE_*`)", - "units": "" - }, - { - "name": "pinLabel", - "ctype": "uint8_t", - "desc": "Label for special pin usage (`PIN_LABEL_*` enum, e.g., `PIN_LABEL_LED`). 0 (`PIN_LABEL_NONE`) otherwise", - "units": "", - "enum": "pinLabel_e" - } - ], - "repeating": "for each Motor/Servo timer" + "MSP2_INAV_SET_RATE_DYNAMICS": { + "code": 8289, + "mspv": 2, + "request": { + "payload": [ + { + "name": "sensitivityCenter", + "ctype": "uint8_t", + "desc": "Sets sensitivity at center", + "units": "%" + }, + { + "name": "sensitivityEnd", + "ctype": "uint8_t", + "desc": "Sets sensitivity at ends", + "units": "%" + }, + { + "name": "correctionCenter", + "ctype": "uint8_t", + "desc": "Sets correction at center", + "units": "%" + }, + { + "name": "correctionEnd", + "ctype": "uint8_t", + "desc": "Sets correction at ends", + "units": "%" + }, + { + "name": "weightCenter", + "ctype": "uint8_t", + "desc": "Sets weight at center", + "units": "%" + }, + { + "name": "weightEnd", + "ctype": "uint8_t", + "desc": "Sets weight at ends", + "units": "%" + } + ] + }, + "reply": null, + "notes": "Requires `USE_RATE_DYNAMICS`. Expects 6 bytes.", + "description": "Sets Rate Dynamics configuration parameters for the current control rate profile." + }, + "MSP2_INAV_EZ_TUNE": { + "code": 8304, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Boolean: 1 if EZ-Tune is enabled (`ezTune()->enabled`)", + "units": "" + }, + { + "name": "filterHz", + "ctype": "uint16_t", + "desc": "Filter frequency used during tuning (`ezTune()->filterHz`)", + "units": "" + }, + { + "name": "axisRatio", + "ctype": "uint8_t", + "desc": "Roll vs Pitch axis tuning ratio (`ezTune()->axisRatio`)", + "units": "" + }, + { + "name": "response", + "ctype": "uint8_t", + "desc": "Desired response characteristic (`ezTune()->response`)", + "units": "" + }, + { + "name": "damping", + "ctype": "uint8_t", + "desc": "Desired damping characteristic (`ezTune()->damping`)", + "units": "" + }, + { + "name": "stability", + "ctype": "uint8_t", + "desc": "Stability preference (`ezTune()->stability`)", + "units": "" + }, + { + "name": "aggressiveness", + "ctype": "uint8_t", + "desc": "Aggressiveness preference (`ezTune()->aggressiveness`)", + "units": "" + }, + { + "name": "rate", + "ctype": "uint8_t", + "desc": "Resulting rate setting (`ezTune()->rate`)", + "units": "" + }, + { + "name": "expo", + "ctype": "uint8_t", + "desc": "Resulting expo setting (`ezTune()->expo`)", + "units": "" + }, + { + "name": "snappiness", + "ctype": "uint8_t", + "desc": "Snappiness preference (`ezTune()->snappiness`)", + "units": "" + } + ] + }, + "notes": "Requires `USE_EZ_TUNE`. Calls `ezTuneUpdate()` before sending.", + "description": "Retrieves the current EZ-Tune parameters." }, - "variable_len": "for each Motor/Servo timer", - "notes": "Provides complete usage flags and helps identify pins repurposed for functions like LED strip.", - "description": "Retrieves the full extended output mapping configuration (timer ID, full 32-bit usage flags, and pin label). Supersedes `MSP2_INAV_OUTPUT_MAPPING_EXT`." - }, - "MSP2_INAV_SERVO_CONFIG": { - "code": 8704, - "mspv": 2, - "request": null, - "reply": { - "payload": [ - { - "name": "min", - "ctype": "int16_t", - "desc": "Minimum servo endpoint (`servoParams(i)->min`)", - "units": "PWM" - }, - { - "name": "max", - "ctype": "int16_t", - "desc": "Maximum servo endpoint (`servoParams(i)->max`)", - "units": "PWM" - }, - { - "name": "middle", - "ctype": "int16_t", - "desc": "Middle/Neutral servo position (`servoParams(i)->middle`)", - "units": "PWM" - }, - { - "name": "rate", - "ctype": "int8_t", - "desc": "Servo rate/scaling (`servoParams(i)->rate`)", - "units": "% (-125 to 125)" - } - ], - "repeating": "MAX_SUPPORTED_SERVOS" + "MSP2_INAV_EZ_TUNE_SET": { + "code": 8305, + "mspv": 2, + "request": { + "payload": [ + { + "name": "enabled", + "ctype": "uint8_t", + "desc": "Sets enabled state", + "units": "" + }, + { + "name": "filterHz", + "ctype": "uint16_t", + "desc": "Sets filter frequency", + "units": "" + }, + { + "name": "axisRatio", + "ctype": "uint8_t", + "desc": "Sets axis ratio", + "units": "" + }, + { + "name": "response", + "ctype": "uint8_t", + "desc": "Sets response characteristic", + "units": "" + }, + { + "name": "damping", + "ctype": "uint8_t", + "desc": "Sets damping characteristic", + "units": "" + }, + { + "name": "stability", + "ctype": "uint8_t", + "desc": "Sets stability preference", + "units": "" + }, + { + "name": "aggressiveness", + "ctype": "uint8_t", + "desc": "Sets aggressiveness preference", + "units": "" + }, + { + "name": "rate", + "ctype": "uint8_t", + "desc": "Sets rate setting", + "units": "" + }, + { + "name": "expo", + "ctype": "uint8_t", + "desc": "Sets expo setting", + "units": "" + }, + { + "name": "snappiness", + "ctype": "uint8_t", + "desc": "(Optional) Sets snappiness preference", + "units": "", + "optional": true + } + ] + }, + "reply": null, + "notes": "Requires `USE_EZ_TUNE`. Expects 10 or 11 bytes. Calls `ezTuneUpdate()` after setting parameters.", + "description": "Sets the EZ-Tune parameters and triggers an update." }, - "variable_len": "MAX_SUPPORTED_SERVOS", - "notes": "", - "description": "Retrieves the configuration parameters for all supported servos (min, max, middle, rate). Supersedes `MSP_SERVO_CONFIGURATIONS`." - }, - "MSP2_INAV_SET_SERVO_CONFIG": { - "code": 8705, - "mspv": 2, - "request": { - "payload": [ - { - "name": "servoIndex", - "ctype": "uint8_t", - "desc": "Index of the servo to configure (0 to `MAX_SUPPORTED_SERVOS - 1`)", - "units": "Index" - }, - { - "name": "min", - "ctype": "int16_t", - "desc": "Sets minimum servo endpoint", - "units": "PWM" - }, - { - "name": "max", - "ctype": "int16_t", - "desc": "Sets maximum servo endpoint", - "units": "PWM" - }, - { - "name": "middle", - "ctype": "int16_t", - "desc": "Sets middle/neutral servo position", - "units": "PWM" - }, - { - "name": "rate", - "ctype": "int8_t", - "desc": "Sets servo rate/scaling", - "units": "% (-125 to 125)" - } - ] + "MSP2_INAV_SELECT_MIXER_PROFILE": { + "code": 8320, + "mspv": 2, + "request": { + "payload": [ + { + "name": "mixerProfileIndex", + "ctype": "uint8_t", + "desc": "Index of the mixer profile to activate (0-based)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Expects 1 byte. Will fail if armed. Calls `setConfigMixerProfileAndWriteEEPROM()`. Only applicable if `MAX_MIXER_PROFILE_COUNT` > 1.", + "description": "Selects the active mixer profile and saves configuration." + }, + "MSP2_ADSB_VEHICLE_LIST": { + "code": 8336, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "maxVehicles", + "ctype": "uint8_t", + "desc": "Maximum number of vehicles tracked (`MAX_ADSB_VEHICLES`). 0 if `USE_ADSB` disabled", + "units": "" + }, + { + "name": "callsignLength", + "ctype": "uint8_t", + "desc": "Maximum length of callsign string (`ADSB_CALL_SIGN_MAX_LENGTH`). 0 if `USE_ADSB` disabled", + "units": "" + }, + { + "name": "totalVehicleMsgs", + "ctype": "uint32_t", + "desc": "Total vehicle messages received (`getAdsbStatus()->vehiclesMessagesTotal`). 0 if `USE_ADSB` disabled", + "units": "" + }, + { + "name": "totalHeartbeatMsgs", + "ctype": "uint32_t", + "desc": "Total heartbeat messages received (`getAdsbStatus()->heartbeatMessagesTotal`). 0 if `USE_ADSB` disabled", + "units": "" + }, + { + "repeating": "maxVehicles", + "payload": [ + { + "name": "callsign", + "desc": "Fixed-length callsign from `adsbVehicle->vehicleValues.callsign` (padded with NULs if shorter).", + "ctype": "char", + "array": true, + "array_size": 9, + "array_size_define": "ADSB_CALL_SIGN_MAX_LENGTH", + "units": "" + }, + { + "name": "icao", + "ctype": "uint32_t", + "desc": "ICAO address (`adsbVehicle->vehicleValues.icao`).", + "units": "" + }, + { + "name": "lat", + "ctype": "int32_t", + "desc": "Latitude in degrees * 1e7 (`adsbVehicle->vehicleValues.lat`).", + "units": "1e-7 deg" + }, + { + "name": "lon", + "ctype": "int32_t", + "desc": "Longitude in degrees * 1e7 (`adsbVehicle->vehicleValues.lon`).", + "units": "1e-7 deg" + }, + { + "name": "alt", + "ctype": "int32_t", + "desc": "Altitude above sea level (`adsbVehicle->vehicleValues.alt`).", + "units": "cm" + }, + { + "name": "headingDeg", + "ctype": "uint16_t", + "desc": "Course over ground in whole degrees (`CENTIDEGREES_TO_DEGREES(vehicleValues.heading)`).", + "units": "deg" + }, + { + "name": "tslc", + "ctype": "uint8_t", + "desc": "Time since last communication (`adsbVehicle->vehicleValues.tslc`).", + "units": "s" + }, + { + "name": "emitterType", + "ctype": "uint8_t", + "desc": "Emitter category (`adsbVehicle->vehicleValues.emitterType`) (refers to enum 'ADSB_EMITTER_TYPE', but none found)", + "units": "" + }, + { + "name": "ttl", + "ctype": "uint8_t", + "desc": "TTL counter used for list maintenance (`adsbVehicle->ttl`).", + "units": "" + } + ] + } + ] + }, + "variable_len": "maxVehicles", + "notes": "Requires `USE_ADSB`. Only a subset of `adsbVehicle_t` is transmitted (callsign, core values, heading in whole degrees, TSLC, emitter type, TTL).", + "description": "Retrieves the list of currently tracked ADSB (Automatic Dependent Surveillance–Broadcast) vehicles. See `adsbVehicle_t` and `adsbVehicleValues_t` in `io/adsb.h` for the exact structure fields." + }, + "MSP2_INAV_CUSTOM_OSD_ELEMENTS": { + "code": 8448, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "maxElements", + "ctype": "uint8_t", + "desc": "Maximum number of custom elements (`MAX_CUSTOM_ELEMENTS`)", + "units": "" + }, + { + "name": "maxTextLength", + "ctype": "uint8_t", + "desc": "Maximum length of the text part (`OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1`)", + "units": "" + }, + { + "name": "maxParts", + "ctype": "uint8_t", + "desc": "Maximum number of parts per element (`CUSTOM_ELEMENTS_PARTS`)", + "units": "" + } + ] + }, + "notes": "Requires `USE_PROGRAMMING_FRAMEWORK`.", + "description": "Retrieves counts related to custom OSD elements defined by the programming framework." }, - "reply": null, - "notes": "Expects 8 bytes. Returns error if index invalid. Calls `servoComputeScalingFactors()`.", - "description": "Sets the configuration parameters for a single servo. Supersedes `MSP_SET_SERVO_CONFIGURATION`." - }, - "MSP2_INAV_GEOZONE": { - "code": 8720, - "mspv": 2, - "request": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Index of the geozone (0 to `MAX_GEOZONES_IN_CONFIG - 1`)", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Index requested", - "units": "" - }, - { - "name": "type", - "ctype": "uint8_t", - "desc": "Define (`GEOZONE_TYPE_EXCLUSIVE/INCLUSIVE`): Zone type (Inclusion/Exclusion)", - "units": "" - }, - { - "name": "shape", - "ctype": "uint8_t", - "desc": "Define (`GEOZONE_SHAPE_CIRCULAR/POLYGON`): Zone shape (Polygon/Circular)", - "units": "" - }, - { - "name": "minAltitude", - "ctype": "int32_t", - "desc": "Minimum allowed altitude within the zone (`geoZonesConfig(idx)->minAltitude`)", - "units": "cm" - }, - { - "name": "maxAltitude", - "ctype": "int32_t", - "desc": "Maximum allowed altitude within the zone (`geoZonesConfig(idx)->maxAltitude`)", - "units": "cm" - }, - { - "name": "isSeaLevelRef", - "ctype": "uint8_t", - "desc": "Boolean: 1 if altitudes are relative to sea level, 0 if relative to home", - "units": "" - }, - { - "name": "fenceAction", - "ctype": "uint8_t", - "desc": "Enum (`fenceAction_e`): Action to take upon boundary violation", - "units": "", - "enum": "fenceAction_e" - }, - { - "name": "vertexCount", - "ctype": "uint8_t", - "desc": "Number of vertices defined for this zone", - "units": "" - } - ] + "MSP2_INAV_CUSTOM_OSD_ELEMENT": { + "code": 8449, + "mspv": 2, + "request": { + "payload": [ + { + "name": "elementIndex", + "ctype": "uint8_t", + "desc": "Index of the custom element (0 to `MAX_CUSTOM_ELEMENTS - 1`)" + } + ] + }, + "reply": { + "payload": [ + { + "repeating": "CUSTOM_ELEMENTS_PARTS", + "payload": [ + { + "name": "partType", + "ctype": "uint8_t", + "enum": "osdCustomElementType_e", + "desc": "Type of this part" + }, + { + "name": "partValue", + "ctype": "uint16_t", + "desc": "Value/ID associated with this part" + } + ] + }, + { + "name": "visibilityType", + "ctype": "uint8_t", + "enum": "osdCustomElementTypeVisibility_e", + "desc": "Visibility condition source" + }, + { + "name": "visibilityValue", + "ctype": "uint16_t", + "desc": "Value/ID of the visibility condition source" + }, + { + "name": "elementText", + "desc": "Static text bytes", + "ctype": "char", + "array": true, + "array_size": 0, + "array_size_define": "OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1" + } + ] + }, + "notes": "Reply emitted only if idx < MAX_CUSTOM_ELEMENTS; otherwise no body is written.", + "description": "Gets the configuration of a single custom OSD element defined by the programming framework." }, - "notes": "Requires `USE_GEOZONE`. Used by `mspFcGeozoneOutCommand`.", - "description": "Get configuration for a specific Geozone." - }, - "MSP2_INAV_SET_GEOZONE": { - "code": 8721, - "mspv": 2, - "request": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Index of the geozone (0 to `MAX_GEOZONES_IN_CONFIG - 1`)", - "units": "" - }, - { - "name": "type", - "ctype": "uint8_t", - "desc": "Define (`GEOZONE_TYPE_EXCLUSIVE/INCLUSIVE`): Zone type (Inclusion/Exclusion)", - "units": "" - }, - { - "name": "shape", - "ctype": "uint8_t", - "desc": "Define (`GEOZONE_SHAPE_CIRCULAR/POLYGON`): Zone shape (Polygon/Circular)", - "units": "" - }, - { - "name": "minAltitude", - "ctype": "int32_t", - "desc": "Minimum allowed altitude (`geoZonesConfigMutable()->minAltitude`)", - "units": "cm" - }, - { - "name": "maxAltitude", - "ctype": "int32_t", - "desc": "Maximum allowed altitude (`geoZonesConfigMutable()->maxAltitude`)", - "units": "cm" - }, - { - "name": "isSeaLevelRef", - "ctype": "uint8_t", - "desc": "Boolean: Altitude reference", - "units": "" - }, - { - "name": "fenceAction", - "ctype": "uint8_t", - "desc": "Enum (`fenceAction_e`): Action to take upon boundary violation", - "units": "", - "enum": "fenceAction_e" - }, - { - "name": "vertexCount", - "ctype": "uint8_t", - "desc": "Number of vertices to be defined (used for validation later)", - "units": "" - } - ] + "MSP2_INAV_SET_CUSTOM_OSD_ELEMENTS": { + "code": 8450, + "mspv": 2, + "request": { + "payload": [ + { + "name": "elementIndex", + "ctype": "uint8_t", + "desc": "Index of the custom element (0 to `MAX_CUSTOM_ELEMENTS - 1`)" + }, + { + "repeating": "CUSTOM_ELEMENTS_PARTS", + "payload": [ + { + "name": "partType", + "ctype": "uint8_t", + "enum": "osdCustomElementType_e", + "desc": "Type of this part" + }, + { + "name": "partValue", + "ctype": "uint16_t", + "desc": "Value/ID associated with this part" + } + ] + }, + { + "name": "visibilityType", + "ctype": "uint8_t", + "enum": "osdCustomElementTypeVisibility_e", + "desc": "Visibility condition source" + }, + { + "name": "visibilityValue", + "ctype": "uint16_t", + "desc": "Value/ID of the visibility condition source" + }, + { + "name": "elementText", + "desc": "Raw bytes", + "ctype": "char", + "array": true, + "array_size": 0, + "array_size_define": "OSD_CUSTOM_ELEMENT_TEXT_SIZE - 1" + } + ] + }, + "reply": null, + "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.", + "description": "Sets the configuration of one custom OSD element." + }, + "MSP2_INAV_OUTPUT_MAPPING_EXT2": { + "code": 8461, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "timerId", + "ctype": "uint8_t", + "desc": "Hardware timer identifier (e.g., `TIM1`, `TIM2`). SITL uses index", + "units": "" + }, + { + "name": "usageFlags", + "ctype": "uint32_t", + "desc": "Full 32-bit timer usage flags (`TIM_USE_*`)", + "units": "" + }, + { + "name": "pinLabel", + "ctype": "uint8_t", + "desc": "Label for special pin usage (`PIN_LABEL_*` enum, e.g., `PIN_LABEL_LED`). 0 (`PIN_LABEL_NONE`) otherwise", + "units": "", + "enum": "pinLabel_e" + } + ], + "repeating": "for each Motor/Servo timer" + }, + "variable_len": "for each Motor/Servo timer", + "notes": "Provides complete usage flags and helps identify pins repurposed for functions like LED strip.", + "description": "Retrieves the full extended output mapping configuration (timer ID, full 32-bit usage flags, and pin label). Supersedes `MSP2_INAV_OUTPUT_MAPPING_EXT`." + }, + "MSP2_INAV_SERVO_CONFIG": { + "code": 8704, + "mspv": 2, + "request": null, + "reply": { + "payload": [ + { + "name": "min", + "ctype": "int16_t", + "desc": "Minimum servo endpoint (`servoParams(i)->min`)", + "units": "PWM" + }, + { + "name": "max", + "ctype": "int16_t", + "desc": "Maximum servo endpoint (`servoParams(i)->max`)", + "units": "PWM" + }, + { + "name": "middle", + "ctype": "int16_t", + "desc": "Middle/Neutral servo position (`servoParams(i)->middle`)", + "units": "PWM" + }, + { + "name": "rate", + "ctype": "int8_t", + "desc": "Servo rate/scaling (`servoParams(i)->rate`)", + "units": "% (-125 to 125)" + } + ], + "repeating": "MAX_SUPPORTED_SERVOS" + }, + "variable_len": "MAX_SUPPORTED_SERVOS", + "notes": "", + "description": "Retrieves the configuration parameters for all supported servos (min, max, middle, rate). Supersedes `MSP_SERVO_CONFIGURATIONS`." }, - "reply": null, - "notes": "Requires `USE_GEOZONE`. Expects 14 bytes. Returns error if index invalid. Calls `geozoneResetVertices()`. Vertices must be set subsequently using `MSP2_INAV_SET_GEOZONE_VERTEX`.", - "description": "Sets the main configuration for a specific Geozone (type, shape, altitude, action). **This command resets (clears) all vertices associated with the zone.**" - }, - "MSP2_INAV_GEOZONE_VERTEX": { - "code": 8722, - "mspv": 2, - "request": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Index of the geozone", - "units": "" - }, - { - "name": "vertexId", - "ctype": "uint8_t", - "desc": "Index of the vertex within the zone (0-based). For circles, 0 = center", - "units": "" - } - ] - }, - "reply": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Geozone index requested", - "units": "Index" - }, - { - "name": "vertexId", - "ctype": "uint8_t", - "desc": "Vertex index requested", - "units": "Index" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Vertex latitude", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Vertex longitude", - "units": "deg * 1e7" - }, - { - "name": "radius", - "ctype": "int32_t", - "desc": "If vertex is circle, Radius of the circular zone", - "units": "cm", - "optional": true - } - ] + "MSP2_INAV_SET_SERVO_CONFIG": { + "code": 8705, + "mspv": 2, + "request": { + "payload": [ + { + "name": "servoIndex", + "ctype": "uint8_t", + "desc": "Index of the servo to configure (0 to `MAX_SUPPORTED_SERVOS - 1`)", + "units": "Index" + }, + { + "name": "min", + "ctype": "int16_t", + "desc": "Sets minimum servo endpoint", + "units": "PWM" + }, + { + "name": "max", + "ctype": "int16_t", + "desc": "Sets maximum servo endpoint", + "units": "PWM" + }, + { + "name": "middle", + "ctype": "int16_t", + "desc": "Sets middle/neutral servo position", + "units": "PWM" + }, + { + "name": "rate", + "ctype": "int8_t", + "desc": "Sets servo rate/scaling", + "units": "% (-125 to 125)" + } + ] + }, + "reply": null, + "notes": "Expects 8 bytes. Returns error if index invalid. Calls `servoComputeScalingFactors()`.", + "description": "Sets the configuration parameters for a single servo. Supersedes `MSP_SET_SERVO_CONFIGURATION`." }, - "variable_len": true, - "notes": "Requires `USE_GEOZONE`. Returns error if indexes are invalid or vertex doesn't exist. For circular zones, the radius is stored internally as the 'latitude' of the vertex with index 1.", - "description": "Get a specific vertex (or center+radius for circular zones) of a Geozone." - }, - "MSP2_INAV_SET_GEOZONE_VERTEX": { - "code": 8723, - "mspv": 2, - "variants": { - "polygon": { - "description": "Polygonal Geozone", - "request": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Geozone index requested", - "units": "Index" - }, - { - "name": "vertexId", - "ctype": "uint8_t", - "desc": "Vertex index requested", - "units": "Index" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Vertex latitude", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Vertex longitude", - "units": "deg * 1e7" - } - ] - }, - "reply": { - "payload": null - } + "MSP2_INAV_GEOZONE": { + "code": 8720, + "mspv": 2, + "request": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Index of the geozone (0 to `MAX_GEOZONES_IN_CONFIG - 1`)", + "units": "" + } + ] }, - "circle": { - "description": "Circular Geozone", - "request": { - "payload": [ - { - "name": "geozoneIndex", - "ctype": "uint8_t", - "desc": "Geozone index requested", - "units": "Index" - }, - { - "name": "vertexId", - "ctype": "uint8_t", - "desc": "Vertex index requested", - "units": "Index" - }, - { - "name": "latitude", - "ctype": "int32_t", - "desc": "Vertex/Center latitude", - "units": "deg * 1e7" - }, - { - "name": "longitude", - "ctype": "int32_t", - "desc": "Vertex/Center longitude", - "units": "deg * 1e7" - }, - { - "name": "radius", - "ctype": "int32_t", - "desc": "Radius of the circular zone", - "units": "cm" - } - ] - }, - "reply": { - "payload": null - } - } + "reply": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Index requested", + "units": "" + }, + { + "name": "type", + "ctype": "uint8_t", + "desc": "Define (`GEOZONE_TYPE_EXCLUSIVE/INCLUSIVE`): Zone type (Inclusion/Exclusion)", + "units": "" + }, + { + "name": "shape", + "ctype": "uint8_t", + "desc": "Define (`GEOZONE_SHAPE_CIRCULAR/POLYGON`): Zone shape (Polygon/Circular)", + "units": "" + }, + { + "name": "minAltitude", + "ctype": "int32_t", + "desc": "Minimum allowed altitude within the zone (`geoZonesConfig(idx)->minAltitude`)", + "units": "cm" + }, + { + "name": "maxAltitude", + "ctype": "int32_t", + "desc": "Maximum allowed altitude within the zone (`geoZonesConfig(idx)->maxAltitude`)", + "units": "cm" + }, + { + "name": "isSeaLevelRef", + "ctype": "uint8_t", + "desc": "Boolean: 1 if altitudes are relative to sea level, 0 if relative to home", + "units": "" + }, + { + "name": "fenceAction", + "ctype": "uint8_t", + "desc": "Enum (`fenceAction_e`): Action to take upon boundary violation", + "units": "", + "enum": "fenceAction_e" + }, + { + "name": "vertexCount", + "ctype": "uint8_t", + "desc": "Number of vertices defined for this zone", + "units": "" + } + ] + }, + "notes": "Requires `USE_GEOZONE`. Used by `mspFcGeozoneOutCommand`.", + "description": "Get configuration for a specific Geozone." }, - "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": "" - } - ] + "MSP2_INAV_SET_GEOZONE": { + "code": 8721, + "mspv": 2, + "request": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Index of the geozone (0 to `MAX_GEOZONES_IN_CONFIG - 1`)", + "units": "" + }, + { + "name": "type", + "ctype": "uint8_t", + "desc": "Define (`GEOZONE_TYPE_EXCLUSIVE/INCLUSIVE`): Zone type (Inclusion/Exclusion)", + "units": "" + }, + { + "name": "shape", + "ctype": "uint8_t", + "desc": "Define (`GEOZONE_SHAPE_CIRCULAR/POLYGON`): Zone shape (Polygon/Circular)", + "units": "" + }, + { + "name": "minAltitude", + "ctype": "int32_t", + "desc": "Minimum allowed altitude (`geoZonesConfigMutable()->minAltitude`)", + "units": "cm" + }, + { + "name": "maxAltitude", + "ctype": "int32_t", + "desc": "Maximum allowed altitude (`geoZonesConfigMutable()->maxAltitude`)", + "units": "cm" + }, + { + "name": "isSeaLevelRef", + "ctype": "uint8_t", + "desc": "Boolean: Altitude reference", + "units": "" + }, + { + "name": "fenceAction", + "ctype": "uint8_t", + "desc": "Enum (`fenceAction_e`): Action to take upon boundary violation", + "units": "", + "enum": "fenceAction_e" + }, + { + "name": "vertexCount", + "ctype": "uint8_t", + "desc": "Number of vertices to be defined (used for validation later)", + "units": "" + } + ] + }, + "reply": null, + "notes": "Requires `USE_GEOZONE`. Expects 14 bytes. Returns error if index invalid. Calls `geozoneResetVertices()`. Vertices must be set subsequently using `MSP2_INAV_SET_GEOZONE_VERTEX`.", + "description": "Sets the main configuration for a specific Geozone (type, shape, altitude, action). **This command resets (clears) all vertices associated with the zone.**" }, - "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, - "request": null, - "reply": { - "payload": [ - { - "name": "roll", - "ctype": "int16_t", - "desc": "Roll angle (`attitude.values.roll`)", - "units": "deci-degrees" - }, - { - "name": "pitch", - "ctype": "int16_t", - "desc": "Pitch angle (`attitude.values.pitch`)", - "units": "deci-degrees" - }, - { - "name": "yaw", - "ctype": "int16_t", - "desc": "Yaw/Heading angle (`attitude.values.yaw`)", - "units": "deci-degrees" - }, - { - "name": "localPositionNorth", - "ctype": "int32_t", - "desc": "Estimated North coordinate in local NEU frame (`posControl.actualState.abs.pos.x`)", - "units": "cm" - }, - { - "name": "localVelocityNorth", - "ctype": "int16_t", - "desc": "Estimated North component of velocity in local NEU frame (`posControl.actualState.abs.vel.x`)", - "units": "cm/s" - }, - { - "name": "localPositionEast", - "ctype": "int32_t", - "desc": "Estimated East coordinate in local NEU frame (`posControl.actualState.abs.pos.y`)", - "units": "cm" - }, - { - "name": "localVelocityEast", - "ctype": "int16_t", - "desc": "Estimated East component of velocity in local NEU frame (`posControl.actualState.abs.vel.y`)", - "units": "cm/s" - }, - { - "name": "localPositionUp", - "ctype": "int32_t", - "desc": "Estimated Up coordinate in local NEU frame (`posControl.actualState.abs.pos.z`)", - "units": "cm" + "MSP2_INAV_GEOZONE_VERTEX": { + "code": 8722, + "mspv": 2, + "request": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Index of the geozone", + "units": "" + }, + { + "name": "vertexId", + "ctype": "uint8_t", + "desc": "Index of the vertex within the zone (0-based). For circles, 0 = center", + "units": "" + } + ] + }, + "reply": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Geozone index requested", + "units": "Index" + }, + { + "name": "vertexId", + "ctype": "uint8_t", + "desc": "Vertex index requested", + "units": "Index" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Vertex latitude", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Vertex longitude", + "units": "deg * 1e7" + }, + { + "name": "radius", + "ctype": "int32_t", + "desc": "If vertex is circle, Radius of the circular zone", + "units": "cm", + "optional": true + } + ] + }, + "variable_len": true, + "notes": "Requires `USE_GEOZONE`. Returns error if indexes are invalid or vertex doesn't exist. For circular zones, the radius is stored internally as the 'latitude' of the vertex with index 1.", + "description": "Get a specific vertex (or center+radius for circular zones) of a Geozone." + }, + "MSP2_INAV_SET_GEOZONE_VERTEX": { + "code": 8723, + "mspv": 2, + "variants": { + "polygon": { + "description": "Polygonal Geozone", + "request": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Geozone index requested", + "units": "Index" + }, + { + "name": "vertexId", + "ctype": "uint8_t", + "desc": "Vertex index requested", + "units": "Index" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Vertex latitude", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Vertex longitude", + "units": "deg * 1e7" + } + ] + }, + "reply": { + "payload": null + } }, - { - "name": "localVelocityUp", - "ctype": "int16_t", - "desc": "Estimated Up component of velocity in local NEU frame (`posControl.actualState.abs.vel.z`)", - "units": "cm/s" + "circle": { + "description": "Circular Geozone", + "request": { + "payload": [ + { + "name": "geozoneIndex", + "ctype": "uint8_t", + "desc": "Geozone index requested", + "units": "Index" + }, + { + "name": "vertexId", + "ctype": "uint8_t", + "desc": "Vertex index requested", + "units": "Index" + }, + { + "name": "latitude", + "ctype": "int32_t", + "desc": "Vertex/Center latitude", + "units": "deg * 1e7" + }, + { + "name": "longitude", + "ctype": "int32_t", + "desc": "Vertex/Center longitude", + "units": "deg * 1e7" + }, + { + "name": "radius", + "ctype": "int32_t", + "desc": "Radius of the circular zone", + "units": "cm" + } + ] + }, + "reply": { + "payload": null + } } - ] + }, + "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." }, - "notes": "All attitude angles are in deci-degrees.", - "description": "Provides estimates of current attitude, local NEU position, and velocity." - }, - "MSP2_BETAFLIGHT_BIND": { - "code": 12288, - "mspv": 2, - "request": null, - "reply": null, - "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.", - "description": "Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2)." + "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, + "request": null, + "reply": { + "payload": [ + { + "name": "roll", + "ctype": "int16_t", + "desc": "Roll angle (`attitude.values.roll`)", + "units": "deci-degrees" + }, + { + "name": "pitch", + "ctype": "int16_t", + "desc": "Pitch angle (`attitude.values.pitch`)", + "units": "deci-degrees" + }, + { + "name": "yaw", + "ctype": "int16_t", + "desc": "Yaw/Heading angle (`attitude.values.yaw`)", + "units": "deci-degrees" + }, + { + "name": "localPositionNorth", + "ctype": "int32_t", + "desc": "Estimated North coordinate in local NEU frame (`posControl.actualState.abs.pos.x`)", + "units": "cm" + }, + { + "name": "localVelocityNorth", + "ctype": "int16_t", + "desc": "Estimated North component of velocity in local NEU frame (`posControl.actualState.abs.vel.x`)", + "units": "cm/s" + }, + { + "name": "localPositionEast", + "ctype": "int32_t", + "desc": "Estimated East coordinate in local NEU frame (`posControl.actualState.abs.pos.y`)", + "units": "cm" + }, + { + "name": "localVelocityEast", + "ctype": "int16_t", + "desc": "Estimated East component of velocity in local NEU frame (`posControl.actualState.abs.vel.y`)", + "units": "cm/s" + }, + { + "name": "localPositionUp", + "ctype": "int32_t", + "desc": "Estimated Up coordinate in local NEU frame (`posControl.actualState.abs.pos.z`)", + "units": "cm" + }, + { + "name": "localVelocityUp", + "ctype": "int16_t", + "desc": "Estimated Up component of velocity in local NEU frame (`posControl.actualState.abs.vel.z`)", + "units": "cm/s" + } + ] + }, + "notes": "All attitude angles are in deci-degrees.", + "description": "Provides estimates of current attitude, local NEU position, and velocity." + }, + "MSP2_BETAFLIGHT_BIND": { + "code": 12288, + "mspv": 2, + "request": null, + "reply": null, + "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.", + "description": "Initiates the receiver binding procedure for supported serial protocols (CRSF, SRXL2)." + } } -} +} \ No newline at end of file diff --git a/docs/development/msp/rev b/docs/development/msp/rev deleted file mode 100644 index b8626c4cff2..00000000000 --- a/docs/development/msp/rev +++ /dev/null @@ -1 +0,0 @@ -4