diff --git a/.github/workflows/docs-orchestrator.yml b/.github/workflows/docs-orchestrator.yml new file mode 100644 index 000000000000..99a86ae5dd55 --- /dev/null +++ b/.github/workflows/docs-orchestrator.yml @@ -0,0 +1,362 @@ +name: Docs - Orchestrator + +on: + push: + branches: + - "main" + - "release/**" + paths: + - "docs/**" + pull_request: + paths: + - "docs/**" + workflow_dispatch: + +permissions: + contents: write + actions: read + id-token: write + +concurrency: + group: docs-orchestrator-${{ github.ref }} + cancel-in-progress: true + +jobs: + # ============================================================================= + # Detect Changes (PR only) + # ============================================================================= + detect-changes: + name: "Detect Changed Paths" + if: github.event_name == 'pull_request' + runs-on: ubuntu-latest + outputs: + source_changed: ${{ steps.changes.outputs.source }} + steps: + - uses: actions/checkout@v4 + - uses: dorny/paths-filter@v3 + id: changes + with: + filters: | + source: + - 'src/**' + - 'msg/**' + - 'ROMFS/**' + - 'Tools/module_config/**' + + # ============================================================================= + # PR Metadata Regen (conditional - only when PR touches source files) + # ============================================================================= + pr-metadata-regen: + name: "PR: Generate Metadata" + needs: [detect-changes] + if: github.event_name == 'pull_request' && needs.detect-changes.outputs.source_changed == 'true' + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + container: + image: px4io/px4-dev-nuttx-focal:2024-11-07 + steps: + - uses: runs-on/action@v1 + + - name: Checkout + uses: actions/checkout@v4 + with: + submodules: recursive + + - name: Cache Restore - ccache + id: cache-ccache + uses: actions/cache/restore@v4 + with: + path: ~/.ccache + key: ccache-docs-metadata-${{ github.sha }} + restore-keys: | + ccache-docs-metadata- + + - name: Setup ccache + run: | + mkdir -p ~/.ccache + echo "max_size = 1G" > ~/.ccache/ccache.conf + + - name: Build px4_sitl_default + run: | + make px4_sitl_default + env: + CCACHE_DIR: ~/.ccache + + - name: Install Emscripten + run: | + git clone https://github.com/emscripten-core/emsdk.git /opt/emsdk + cd /opt/emsdk + ./emsdk install 3.1.64 + ./emsdk activate 3.1.64 + + - name: Build failsafe_web + run: | + source /opt/emsdk/emsdk_env.sh + make failsafe_web + + - name: Sync all metadata + run: Tools/ci/metadata_sync.sh --sync all + + - name: Upload metadata artifact + uses: actions/upload-artifact@v4 + with: + name: pr-metadata + path: docs/ + retention-days: 1 + + # ============================================================================= + # Push Metadata Regen (main/release branches) + # ============================================================================= + metadata-regen: + name: "Push: Generate & Commit Metadata" + if: github.event_name == 'push' + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + container: + image: px4io/px4-dev-nuttx-focal:2024-11-07 + steps: + - uses: runs-on/action@v1 + + - name: Checkout + uses: actions/checkout@v4 + with: + submodules: recursive + token: ${{ secrets.PX4BUILTBOT_PERSONAL_ACCESS_TOKEN }} + + - name: Cache Restore - ccache + id: cache-ccache + uses: actions/cache/restore@v4 + with: + path: ~/.ccache + key: ccache-docs-metadata-${{ github.sha }} + restore-keys: | + ccache-docs-metadata- + + - name: Setup ccache + run: | + mkdir -p ~/.ccache + echo "max_size = 1G" > ~/.ccache/ccache.conf + + - name: Build px4_sitl_default + run: | + make px4_sitl_default + env: + CCACHE_DIR: ~/.ccache + + - name: Cache Save - ccache + uses: actions/cache/save@v4 + if: always() + with: + path: ~/.ccache + key: ccache-docs-metadata-${{ github.sha }} + + - name: Install Emscripten + run: | + git clone https://github.com/emscripten-core/emsdk.git /opt/emsdk + cd /opt/emsdk + ./emsdk install 3.1.64 + ./emsdk activate 3.1.64 + + - name: Build failsafe_web + run: | + source /opt/emsdk/emsdk_env.sh + make failsafe_web + + - name: Sync all metadata + run: Tools/ci/metadata_sync.sh --sync all + + - name: Setup Node.js + uses: actions/setup-node@v4 + with: + node-version: 20 + cache: npm + cache-dependency-path: ./docs/yarn.lock + + - name: Format markdown with Prettier + run: | + cd docs + yarn install --frozen-lockfile + yarn prettier --write "en/**/*.md" + + - name: Commit and push changes + run: | + git config --global user.name "${{ secrets.PX4BUILDBOT_USER }}" + git config --global user.email "${{ secrets.PX4BUILDBOT_EMAIL }}" + git add docs/ + if git diff --staged --quiet; then + echo "No changes to commit" + else + git commit -m "docs: auto-sync metadata + + Co-Authored-By: PX4 BuildBot <${{ secrets.PX4BUILDBOT_EMAIL }}>" + git push + fi + + # ============================================================================= + # Link Check + # ============================================================================= + link-check: + name: "Check Links" + needs: [detect-changes, pr-metadata-regen] + if: always() && (github.event_name == 'pull_request') + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@v4 + with: + ref: ${{ github.event.pull_request.head.sha }} + + - name: Download metadata artifact + if: needs.pr-metadata-regen.result == 'success' + uses: actions/download-artifact@v4 + with: + name: pr-metadata + path: docs/ + + - name: Setup Node.js + uses: actions/setup-node@v4 + with: + node-version: 20 + + - name: Run link checker + run: | + npm -g install markdown_link_checker_sc@0.0.138 + mkdir -p logs + markdown_link_checker_sc \ + -r "$GITHUB_WORKSPACE" \ + -d docs \ + -e en \ + -i assets \ + -u docs.px4.io/main/ \ + > ./logs/link-check-results.md || true + cat ./logs/link-check-results.md + + - name: Upload link check results + uses: actions/upload-artifact@v4 + with: + name: link-check-results + path: logs/link-check-results.md + retention-days: 7 + + # ============================================================================= + # Build Site + # ============================================================================= + build-site: + name: "Build Site" + needs: [detect-changes, pr-metadata-regen, metadata-regen] + if: always() && (needs.metadata-regen.result == 'success' || needs.metadata-regen.result == 'skipped') + runs-on: [runs-on,runner=4cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=false,extras=s3-cache] + outputs: + branchname: ${{ steps.set-branch.outputs.branchname }} + releaseversion: ${{ steps.set-version.outputs.releaseversion }} + steps: + - uses: runs-on/action@v1 + + - name: Checkout + uses: actions/checkout@v4 + with: + ref: ${{ github.event_name == 'pull_request' && github.event.pull_request.head.sha || github.sha }} + + - name: Download metadata artifact (PR) + if: github.event_name == 'pull_request' && needs.pr-metadata-regen.result == 'success' + uses: actions/download-artifact@v4 + with: + name: pr-metadata + path: docs/ + + - id: set-branch + run: echo "branchname=${GITHUB_HEAD_REF:-${GITHUB_REF#refs/heads/}}" >> $GITHUB_OUTPUT + + - id: set-version + run: | + branch="${{ steps.set-branch.outputs.branchname }}" + if [[ "$branch" == "main" ]]; then + version="main" + else + version="v${branch#release/}" + fi + echo "releaseversion=$version" >> $GITHUB_OUTPUT + + - name: Setup Node + uses: actions/setup-node@v4 + with: + node-version: 20 + cache: npm + cache-dependency-path: ./docs/yarn.lock + + - name: Install dependencies + run: yarn install --frozen-lockfile --cwd ./docs + + - name: Build with VitePress + working-directory: ./docs + env: + BRANCH_NAME: ${{ steps.set-version.outputs.releaseversion }} + run: | + npm run docs:build_ubuntu + touch .vitepress/dist/.nojekyll + npm run docs:sitemap + + - name: Upload artifact + uses: actions/upload-artifact@v4 + with: + name: px4_docs_build + path: docs/.vitepress/dist/ + retention-days: 1 + + # ============================================================================= + # Deploy to AWS (push only) + # ============================================================================= + deploy-aws: + name: "Deploy to AWS" + if: github.event_name == 'push' + needs: [metadata-regen, build-site] + runs-on: ubuntu-latest + steps: + - name: Download Artifact + uses: actions/download-artifact@v4 + with: + name: px4_docs_build + path: ~/_book + + - name: Configure AWS from OIDC + uses: aws-actions/configure-aws-credentials@v4 + with: + role-to-assume: ${{ secrets.AWS_ROLE_ARN }} + aws-region: us-west-2 + + - name: Sanity check AWS credentials + run: aws sts get-caller-identity + + - name: Upload HTML with short cache + run: | + aws s3 sync ~/_book/ s3://px4-docs/${{ needs.build-site.outputs.releaseversion }}/ \ + --delete \ + --exclude "*" --include "*.html" \ + --cache-control "public, max-age=60" + + - name: Upload assets with long cache + run: | + aws s3 sync ~/_book/ s3://px4-docs/${{ needs.build-site.outputs.releaseversion }}/ \ + --delete \ + --exclude "*.html" \ + --cache-control "public, max-age=86400, immutable" + + # ============================================================================= + # Crowdin Upload (push only) + # ============================================================================= + crowdin-upload: + name: "Upload to Crowdin" + if: github.event_name == 'push' && github.ref == 'refs/heads/main' + needs: [metadata-regen, build-site] + runs-on: ubuntu-latest + steps: + - name: Checkout + uses: actions/checkout@v4 + + - name: Upload to Crowdin + uses: crowdin/github-action@v2 + with: + upload_sources: true + upload_translations: false + download_translations: false + source: docs/en/**/*.md + project_id: ${{ secrets.CROWDIN_PROJECT_ID }} + token: ${{ secrets.CROWDIN_PERSONAL_TOKEN }} diff --git a/.github/workflows/docs_metadata_check.yml b/.github/workflows/docs_metadata_check.yml new file mode 100644 index 000000000000..b9a0ad3572cc --- /dev/null +++ b/.github/workflows/docs_metadata_check.yml @@ -0,0 +1,49 @@ +name: Docs Metadata Checks + +permissions: + contents: write + +on: + pull_request: {} + push: + branches: + - main + - 'release/**' + +jobs: + metadata-check: + name: ${{ matrix.name }} metadata + runs-on: [runs-on,runner=2cpu-linux-x64,image=ubuntu24-full-x64,"run-id=${{ github.run_id }}",spot=true] + container: + image: ghcr.io/px4/px4-dev:v1.16.0-ondemand + strategy: + fail-fast: false + matrix: + include: + - name: uORB Graphs + script: Tools/ci/metadata_uorb_graph.sh + # - name: Failsafe Web + # script: Tools/ci/metadata_failsafe_web.sh + - name: uORB Messages + script: Tools/ci/metadata_msg_docs.sh + - name: Parameter Reference + script: Tools/ci/metadata_parameters.sh + - name: Airframe Reference + script: Tools/ci/metadata_airframe.sh + - name: Module Reference + script: Tools/ci/metadata_modules.sh + steps: + - name: Checkout repository + uses: actions/checkout@v4 + with: + persist-credentials: true + + - name: Mark all directories safe for Git + run: git config --system --add safe.directory '*' + + - name: Run ${{ matrix.name }} metadata check + run: ${{ matrix.script }} --test-only + + - name: Setup tmate session + if: ${{ failure() }} + uses: mxschmitt/action-tmate@v3 diff --git a/.gitignore b/.gitignore index f90db3cf6fe2..fcf982c8df20 100644 --- a/.gitignore +++ b/.gitignore @@ -109,3 +109,6 @@ src/systemcmds/topic_listener/listener_generated.cpp # colcon log/ keys/ + +# metadata +_emscripten_sdk/ diff --git a/Makefile b/Makefile index 3639bbdee403..2d3336320657 100644 --- a/Makefile +++ b/Makefile @@ -598,3 +598,10 @@ failsafe_web: run_failsafe_web_server: failsafe_web @cd build/px4_sitl_default_failsafe_web && \ python3 -m http.server + +# Generate reference documentation for uORB messages +.PHONY: msg_docs +msg_docs: + $(call colorecho,'Generating uORB message reference docs') + @mkdir -p build/msg_docs + @./Tools/msg/generate_msg_docs.py -d build/msg_docs diff --git a/Tools/ci/metadata_sync.sh b/Tools/ci/metadata_sync.sh new file mode 100755 index 000000000000..780bb86ceab2 --- /dev/null +++ b/Tools/ci/metadata_sync.sh @@ -0,0 +1,431 @@ +#!/usr/bin/env bash +# +# metadata_sync.sh - Unified metadata generation and synchronization for PX4 docs +# +# Usage: +# Tools/ci/metadata_sync.sh [OPTIONS] [TYPES...] +# +# Types: +# parameters - Parameter reference (docs/en/advanced_config/parameter_reference.md) +# airframes - Airframe reference (docs/en/airframes/airframe_reference.md) +# modules - Module documentation (docs/en/modules/*.md) +# msg_docs - uORB message docs (docs/en/msg_docs/*.md + docs/en/middleware/dds_topics.md) +# uorb_graphs - uORB graph JSONs (docs/public/middleware/*.json) +# failsafe_web - Failsafe simulator (docs/public/config/failsafe/*.{js,wasm,json}) +# all - All of the above (default) +# +# Options: +# --generate Build the make targets to generate fresh metadata +# --sync Copy generated files to docs/ +# --verbose Show detailed output +# --help Show this help +# +# Exit codes: +# 0 - Success (files synced or already up-to-date) +# 1 - Error (build failed, missing files, etc.) +# +# Examples: +# # Full regeneration and sync (orchestrator use case) +# Tools/ci/metadata_sync.sh --generate --sync all +# +# # Just sync specific type (assumes already built) +# Tools/ci/metadata_sync.sh --sync parameters +# +# # Generate only, don't copy +# Tools/ci/metadata_sync.sh --generate uorb_graphs +# +set -euo pipefail +shopt -s nullglob + +# ═══════════════════════════════════════════════════════════════════════════════ +# Configuration +# ═══════════════════════════════════════════════════════════════════════════════ + +EMSCRIPTEN_VERSION="3.1.64" +EMSDK_DIR="${EMSDK_DIR:-_emscripten_sdk}" + +# All available metadata types +ALL_TYPES=(parameters airframes modules msg_docs uorb_graphs failsafe_web) + +# ═══════════════════════════════════════════════════════════════════════════════ +# Logging +# ═══════════════════════════════════════════════════════════════════════════════ + +VERBOSE=false + +log() { + echo "[metadata_sync] $*" +} + +log_verbose() { + if [[ "$VERBOSE" == "true" ]]; then + echo "[metadata_sync] $*" + fi +} + +die() { + echo "[metadata_sync] ERROR: $*" >&2 + exit 1 +} + +# ═══════════════════════════════════════════════════════════════════════════════ +# Help +# ═══════════════════════════════════════════════════════════════════════════════ + +show_help() { + head -n 35 "$0" | tail -n +2 | sed 's/^# \?//' + exit 0 +} + +# ═══════════════════════════════════════════════════════════════════════════════ +# Emscripten Setup +# ═══════════════════════════════════════════════════════════════════════════════ + +ensure_emscripten() { + if command -v emcc >/dev/null 2>&1; then + log_verbose "Emscripten already available: $(emcc --version | head -1)" + return 0 + fi + + log "Setting up Emscripten ${EMSCRIPTEN_VERSION}..." + + if [[ ! -d "$EMSDK_DIR" ]]; then + log_verbose "Cloning emsdk to $EMSDK_DIR" + if [[ "$VERBOSE" == "true" ]]; then + git clone https://github.com/emscripten-core/emsdk.git "$EMSDK_DIR" + else + git clone https://github.com/emscripten-core/emsdk.git "$EMSDK_DIR" >/dev/null 2>&1 + fi + fi + + pushd "$EMSDK_DIR" >/dev/null + if [[ "$VERBOSE" == "true" ]]; then + ./emsdk install "$EMSCRIPTEN_VERSION" + ./emsdk activate "$EMSCRIPTEN_VERSION" + else + ./emsdk install "$EMSCRIPTEN_VERSION" >/dev/null 2>&1 + ./emsdk activate "$EMSCRIPTEN_VERSION" >/dev/null 2>&1 + fi + popd >/dev/null + + # shellcheck source=/dev/null + source "${EMSDK_DIR}/emsdk_env.sh" >/dev/null 2>&1 + + log_verbose "Emscripten ready: $(emcc --version | head -1)" +} + +# ═══════════════════════════════════════════════════════════════════════════════ +# Generation Functions +# ═══════════════════════════════════════════════════════════════════════════════ + +generate_parameters() { + log "Generating parameters metadata..." + if [[ "$VERBOSE" == "true" ]]; then + make parameters_metadata + else + make parameters_metadata >/dev/null 2>&1 + fi +} + +generate_airframes() { + log "Generating airframes metadata..." + if [[ "$VERBOSE" == "true" ]]; then + make airframe_metadata + else + make airframe_metadata >/dev/null 2>&1 + fi +} + +generate_modules() { + log "Generating modules documentation..." + if [[ "$VERBOSE" == "true" ]]; then + make module_documentation + else + make module_documentation >/dev/null 2>&1 + fi +} + +generate_msg_docs() { + log "Generating message documentation..." + if [[ "$VERBOSE" == "true" ]]; then + make msg_docs + else + make msg_docs >/dev/null 2>&1 + fi +} + +generate_uorb_graphs() { + log "Generating uORB graphs..." + if [[ "$VERBOSE" == "true" ]]; then + make uorb_graphs + else + make uorb_graphs >/dev/null 2>&1 + fi +} + +generate_failsafe_web() { + ensure_emscripten + log "Generating failsafe web..." + if [[ "$VERBOSE" == "true" ]]; then + make failsafe_web + else + make failsafe_web >/dev/null 2>&1 + fi +} + +# ═══════════════════════════════════════════════════════════════════════════════ +# Sync Functions +# ═══════════════════════════════════════════════════════════════════════════════ + +sync_parameters() { + local src="build/px4_sitl_default/docs/parameters.md" + local dest="docs/en/advanced_config/parameter_reference.md" + + log "Syncing parameters..." + + if [[ ! -f "$src" ]]; then + die "Source file not found: $src (did you run --generate?)" + fi + + mkdir -p "$(dirname "$dest")" + cp "$src" "$dest" + log_verbose " $src -> $dest" +} + +sync_airframes() { + local src="build/px4_sitl_default/docs/airframes.md" + local dest="docs/en/airframes/airframe_reference.md" + + log "Syncing airframes..." + + if [[ ! -f "$src" ]]; then + die "Source file not found: $src (did you run --generate?)" + fi + + mkdir -p "$(dirname "$dest")" + cp "$src" "$dest" + log_verbose " $src -> $dest" +} + +sync_modules() { + local src_dir="build/px4_sitl_default/docs/modules" + local dest_dir="docs/en/modules" + + log "Syncing modules..." + + if [[ ! -d "$src_dir" ]]; then + die "Source directory not found: $src_dir (did you run --generate?)" + fi + + local src_files=("$src_dir"/*.md) + if [[ ${#src_files[@]} -eq 0 ]]; then + die "No .md files found in $src_dir" + fi + + mkdir -p "$dest_dir" + + for src in "${src_files[@]}"; do + local name + name=$(basename "$src") + cp "$src" "$dest_dir/$name" + log_verbose " $src -> $dest_dir/$name" + done +} + +sync_msg_docs() { + local src_dir="build/px4_sitl_default/msg_docs" + local dest_dir="docs/en/msg_docs" + local middleware_dir="docs/en/middleware" + + log "Syncing message docs..." + + if [[ ! -d "$src_dir" ]]; then + die "Source directory not found: $src_dir (did you run --generate?)" + fi + + local src_files=("$src_dir"/*.md) + if [[ ${#src_files[@]} -eq 0 ]]; then + die "No .md files found in $src_dir" + fi + + mkdir -p "$dest_dir" + mkdir -p "$middleware_dir" + + for src in "${src_files[@]}"; do + local name + name=$(basename "$src") + + # dds_topics.md goes to middleware dir + if [[ "$name" == "dds_topics.md" ]]; then + cp "$src" "$middleware_dir/$name" + log_verbose " $src -> $middleware_dir/$name" + else + cp "$src" "$dest_dir/$name" + log_verbose " $src -> $dest_dir/$name" + fi + done +} + +sync_uorb_graphs() { + local src_dir="Tools/uorb_graph" + local dest_dir="docs/public/middleware" + + log "Syncing uORB graphs..." + + local src_files=("$src_dir"/*.json) + if [[ ${#src_files[@]} -eq 0 ]]; then + die "No .json files found in $src_dir (did you run --generate?)" + fi + + mkdir -p "$dest_dir" + + for src in "${src_files[@]}"; do + local name + name=$(basename "$src") + cp "$src" "$dest_dir/$name" + log_verbose " $src -> $dest_dir/$name" + done +} + +sync_failsafe_web() { + local src_dir="build/px4_sitl_default_failsafe_web" + local dest_dir="docs/public/config/failsafe" + + log "Syncing failsafe web..." + + if [[ ! -d "$src_dir" ]]; then + die "Source directory not found: $src_dir (did you run --generate?)" + fi + + # Gather js, wasm, json files + local src_files=() + for ext in js wasm json; do + src_files+=("$src_dir"/*."$ext") + done + + if [[ ${#src_files[@]} -eq 0 ]]; then + die "No .js/.wasm/.json files found in $src_dir" + fi + + mkdir -p "$dest_dir" + + for src in "${src_files[@]}"; do + local name + name=$(basename "$src") + cp "$src" "$dest_dir/$name" + log_verbose " $src -> $dest_dir/$name" + done +} + +# ═══════════════════════════════════════════════════════════════════════════════ +# Main Logic +# ═══════════════════════════════════════════════════════════════════════════════ + +DO_GENERATE=false +DO_SYNC=false +SELECTED_TYPES=() + +parse_args() { + while [[ $# -gt 0 ]]; do + case "$1" in + --generate) + DO_GENERATE=true + shift + ;; + --sync) + DO_SYNC=true + shift + ;; + --verbose) + VERBOSE=true + shift + ;; + --help|-h) + show_help + ;; + -*) + die "Unknown option: $1" + ;; + *) + # It's a type + SELECTED_TYPES+=("$1") + shift + ;; + esac + done + + # Default to all types if none specified + if [[ ${#SELECTED_TYPES[@]} -eq 0 ]]; then + SELECTED_TYPES=("all") + fi + + # Expand "all" to all types + local expanded_types=() + for t in "${SELECTED_TYPES[@]}"; do + if [[ "$t" == "all" ]]; then + expanded_types+=("${ALL_TYPES[@]}") + else + expanded_types+=("$t") + fi + done + SELECTED_TYPES=("${expanded_types[@]}") + + # Validate types + for t in "${SELECTED_TYPES[@]}"; do + local valid=false + for valid_type in "${ALL_TYPES[@]}"; do + if [[ "$t" == "$valid_type" ]]; then + valid=true + break + fi + done + if [[ "$valid" == "false" ]]; then + die "Unknown type: $t (valid: ${ALL_TYPES[*]})" + fi + done + + # Must specify at least one action + if [[ "$DO_GENERATE" == "false" && "$DO_SYNC" == "false" ]]; then + die "Must specify at least one of: --generate, --sync" + fi +} + +main() { + parse_args "$@" + + log "Selected types: ${SELECTED_TYPES[*]}" + [[ "$DO_GENERATE" == "true" ]] && log "Actions: generate" + [[ "$DO_SYNC" == "true" ]] && log "Actions: sync" + + # Remove duplicates from SELECTED_TYPES + local -A seen + local unique_types=() + for t in "${SELECTED_TYPES[@]}"; do + if [[ -z "${seen[$t]:-}" ]]; then + seen[$t]=1 + unique_types+=("$t") + fi + done + SELECTED_TYPES=("${unique_types[@]}") + + # Generate phase + if [[ "$DO_GENERATE" == "true" ]]; then + log "=== Generation Phase ===" + for t in "${SELECTED_TYPES[@]}"; do + "generate_$t" + done + fi + + # Sync phase + if [[ "$DO_SYNC" == "true" ]]; then + log "=== Sync Phase ===" + for t in "${SELECTED_TYPES[@]}"; do + "sync_$t" + done + fi + + log "Done." + exit 0 +} + +main "$@" diff --git a/Tools/ci/test_metadata_sync.sh b/Tools/ci/test_metadata_sync.sh new file mode 100755 index 000000000000..55dbc64a722a --- /dev/null +++ b/Tools/ci/test_metadata_sync.sh @@ -0,0 +1,163 @@ +#!/usr/bin/env bash +# +# test_metadata_sync.sh - Test metadata_sync.sh locally using Docker +# +# Usage: +# Tools/ci/test_metadata_sync.sh [OPTIONS] [TYPES...] +# +# Options: +# --shell Drop into interactive shell instead of running sync +# --verbose Pass --verbose to metadata_sync.sh +# --skip-build Skip SITL build (use existing build artifacts) +# --help Show this help +# +# Types: +# Same as metadata_sync.sh: parameters, airframes, modules, msg_docs, uorb_graphs, failsafe_web, all +# +# Examples: +# # Test full regeneration +# Tools/ci/test_metadata_sync.sh all +# +# # Test just parameters (faster) +# Tools/ci/test_metadata_sync.sh parameters +# +# # Drop into shell for debugging +# Tools/ci/test_metadata_sync.sh --shell +# +# # Skip build if you already have artifacts +# Tools/ci/test_metadata_sync.sh --skip-build --verbose all +# +set -euo pipefail + +SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" +REPO_ROOT="$(cd "$SCRIPT_DIR/../.." && pwd)" + +DOCKER_IMAGE="px4io/px4-dev:v1.17.0-alpha1" +CONTAINER_NAME="px4-metadata-test-$$" + +SHELL_MODE=false +VERBOSE="" +SKIP_BUILD=false +TYPES=() + +show_help() { + head -n 28 "$0" | tail -n +2 | sed 's/^# \?//' + exit 0 +} + +cleanup() { + echo "[test] Cleaning up container..." + docker rm -f "$CONTAINER_NAME" 2>/dev/null || true +} + +parse_args() { + while [[ $# -gt 0 ]]; do + case "$1" in + --shell) + SHELL_MODE=true + shift + ;; + --verbose) + VERBOSE="--verbose" + shift + ;; + --skip-build) + SKIP_BUILD=true + shift + ;; + --help|-h) + show_help + ;; + -*) + echo "Unknown option: $1" >&2 + exit 1 + ;; + *) + TYPES+=("$1") + shift + ;; + esac + done + + # Default to all types + if [[ ${#TYPES[@]} -eq 0 ]]; then + TYPES=("all") + fi +} + +main() { + parse_args "$@" + + cd "$REPO_ROOT" + + echo "[test] Using Docker image: $DOCKER_IMAGE" + echo "[test] Repository root: $REPO_ROOT" + + # Pull image if not present + if ! docker image inspect "$DOCKER_IMAGE" >/dev/null 2>&1; then + echo "[test] Pulling Docker image..." + docker pull "$DOCKER_IMAGE" + fi + + trap cleanup EXIT + + # Handle git worktrees: the .git file points to the main repo's .git directory + # We need to mount that directory too so git works inside the container + local git_mounts=() + if [[ -f "$REPO_ROOT/.git" ]]; then + # It's a worktree - read the gitdir path and mount it + local gitdir + gitdir=$(grep '^gitdir:' "$REPO_ROOT/.git" | cut -d' ' -f2) + if [[ -n "$gitdir" ]]; then + # Mount the gitdir at the same path so the .git file reference works + git_mounts+=("-v" "$gitdir:$gitdir:ro") + # Also need the main .git directory (parent of worktrees/) + local main_git_dir + main_git_dir=$(dirname "$(dirname "$gitdir")") + git_mounts+=("-v" "$main_git_dir:$main_git_dir:ro") + echo "[test] Detected git worktree, mounting git directories" + fi + fi + + if [[ "$SHELL_MODE" == "true" ]]; then + echo "[test] Starting interactive shell..." + echo "[test] Run: Tools/ci/metadata_sync.sh --generate --sync all" + docker run -it --rm \ + --name "$CONTAINER_NAME" \ + -v "$REPO_ROOT:/src" \ + "${git_mounts[@]}" \ + -w /src \ + "$DOCKER_IMAGE" \ + /bin/bash + else + echo "[test] Running metadata sync for: ${TYPES[*]}" + + # Build the command + local cmd="" + + if [[ "$SKIP_BUILD" == "false" ]]; then + cmd="Tools/ci/metadata_sync.sh --generate --sync $VERBOSE ${TYPES[*]}" + else + cmd="Tools/ci/metadata_sync.sh --sync $VERBOSE ${TYPES[*]}" + fi + + echo "[test] Command: $cmd" + + docker run --rm \ + --name "$CONTAINER_NAME" \ + -v "$REPO_ROOT:/src" \ + "${git_mounts[@]}" \ + -w /src \ + "$DOCKER_IMAGE" \ + /bin/bash -c "$cmd" + + echo "" + echo "[test] Done! Check git status for changes:" + echo " git status -s docs/" + echo "" + echo "[test] To see what changed:" + echo " git diff docs/" + fi +} + +main "$@" diff --git a/docs/.prettierrc b/docs/.prettierrc new file mode 100644 index 000000000000..8018f0709d06 --- /dev/null +++ b/docs/.prettierrc @@ -0,0 +1,8 @@ +{ + "proseWrap": "preserve", + "tabWidth": 2, + "useTabs": false, + "printWidth": 9999, + "endOfLine": "lf", + "embeddedLanguageFormatting": "off" +} diff --git a/docs/en/advanced/px4_metadata.md b/docs/en/advanced/px4_metadata.md index bc0c61dca722..065b5fcf10be 100644 --- a/docs/en/advanced/px4_metadata.md +++ b/docs/en/advanced/px4_metadata.md @@ -31,6 +31,7 @@ For more information see the topics for each data type: - [Parameters & Configurations > Creating/Defining Parameters](../advanced/parameters_and_configurations.md#creating-defining-parameters) - [Events Interface](../concept/events_interface.md) - [Actuator Metadata](#actuator-metadata) (below) + ## Metadata Toolchain The process for handling metadata is the same for all metadata types. @@ -69,6 +70,7 @@ The parameter XML file of the main branch is copied into the QGC source tree via The following diagram shows how actuator metadata is assembled from the source code and used by QGroundControl: ![Actuators Metadata](../../assets/diagrams/actuator_metadata_processing.svg) + - **Left**: the metadata is defined in `module.yml` files in different modules. diff --git a/docs/en/advanced_config/advanced_flight_controller_orientation_leveling.md b/docs/en/advanced_config/advanced_flight_controller_orientation_leveling.md index c960ab5eb7db..28007b730f6e 100644 --- a/docs/en/advanced_config/advanced_flight_controller_orientation_leveling.md +++ b/docs/en/advanced_config/advanced_flight_controller_orientation_leveling.md @@ -34,4 +34,3 @@ You can locate the parameters in QGroundControl as shown below: Positive angles increase in CCW direction, negative angles increase in CW direction. - [SENS_BOARD_Z_OFF](../advanced_config/parameter_reference.md#SENS_BOARD_Z_OFF): Rotation, in degrees, around PX4FMU's Z axis Yaw axis. Positive angles increase in CCW direction, negative angles increase in CW direction. - diff --git a/docs/en/advanced_config/bootloader_update_v6xrt.md b/docs/en/advanced_config/bootloader_update_v6xrt.md index a868f8e9db16..9d7f92a4aaf2 100644 --- a/docs/en/advanced_config/bootloader_update_v6xrt.md +++ b/docs/en/advanced_config/bootloader_update_v6xrt.md @@ -63,7 +63,6 @@ The tool is available for Windows, Linux and macOS. ![Flash bootloader through Secure provisioning - Step 6](../../assets/advanced_config/bootloader_6xrt/bootloader_update_v6xrt_step6.png) To get the Pixhawk V6X-RT into "ISP bootloader mode" there are 2 options: - 1. Launch QGC connect the Pixhawk select **Analayze Tools** and then **MAVLINK Console**. On the console type `reboot -i`. This will put the Pixhawk V6X-RT into "ISP bootloader mode" diff --git a/docs/en/advanced_config/esc_calibration.md b/docs/en/advanced_config/esc_calibration.md index 45409b993746..c8133ec8709c 100644 --- a/docs/en/advanced_config/esc_calibration.md +++ b/docs/en/advanced_config/esc_calibration.md @@ -89,7 +89,6 @@ To calibrate the ESCs: ::: Verify the following values: - - The minimum value for a motor (default: `1100us`) should make the motor spin slowly but reliably, and also spin up reliably after it was stopped. You can confirm that a motor spins at minimum (still without propellers) in [Actuator Testing](../config/actuators.md#actuator-testing), by enabling the sliders, and then moving the test output slider for the motor to the first snap position from the bottom. diff --git a/docs/en/advanced_config/parameter_reference.md b/docs/en/advanced_config/parameter_reference.md index 71e4262e9064..69618f0b0bb2 100644 --- a/docs/en/advanced_config/parameter_reference.md +++ b/docs/en/advanced_config/parameter_reference.md @@ -10,47 +10,263 @@ If a listed parameter is missing from the Firmware see: [Finding/Updating Parame -## ADC +## UAVCAN Motor Parameters -### ADC_ADS7953_EN (`INT32`) {#ADC_ADS7953_EN} +### ctl_bw (`INT32`) {#ctl_bw} -Enable ADS7953. +Speed controller bandwidth. -Enable the driver for the ADS7953 board +Speed controller bandwidth, in Hz. Higher values result in faster speed and current rise times, but may result in overshoot and higher current consumption. For fixed-wing aircraft, this value should be less than 50 Hz; for multirotors, values up to 100 Hz may provide improvements in responsiveness. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 10 | 250 | | 75 | Hz | -### ADC_ADS7953_REFV (`FLOAT`) {#ADC_ADS7953_REFV} +### ctl_dir (`INT32`) {#ctl_dir} -Applied reference Voltage. +Reverse direction. -The voltage applied to the ADS7953 board as reference +Motor spin direction as detected during initial enumeration. Use 0 or 1 to reverse direction. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 2.0 | 3.0 | 0.01 | 2.5 | V | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | | 1 | -### ADC_TLA2528_EN (`INT32`) {#ADC_TLA2528_EN} +### ctl_gain (`FLOAT`) {#ctl_gain} -Enable TLA2528. +Speed (RPM) controller gain. -Enable the driver for the TLA2528 +Determines controller +aggressiveness; units are amp-seconds per radian. Systems with +higher rotational inertia (large props) will need gain increased; +systems with low rotational inertia (small props) may need gain +decreased. Higher values result in faster response, but may result +in oscillation and excessive overshoot. Lower values result in a +slower, smoother response. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | 0.00 | 1.00 | | 1 | C/rad | -### ADC_TLA2528_REFV (`FLOAT`) {#ADC_TLA2528_REFV} +### ctl_hz_idle (`FLOAT`) {#ctl_hz_idle} -Applied reference Voltage. +Idle speed (e Hz). -The voltage applied to the TLA2528 board as reference +Idle speed (e Hz) -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 2.0 | 3.0 | 0.01 | 2.5 | V | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 3.5 | Hz | + +### ctl_start_rate (`INT32`) {#ctl_start_rate} + +Spin-up rate (e Hz/s). + +Spin-up rate (e Hz/s) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | 5 | 1000 | | 25 | 1/s^2 | + +### esc_index (`INT32`) {#esc_index} + +Index of this ESC in throttle command messages. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 15 | | 0 | + +### id_ext_status (`INT32`) {#id_ext_status} + +Extended status ID. + +Extended status ID + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 1000000 | | 20034 | + +### int_ext_status (`INT32`) {#int_ext_status} + +Extended status interval (µs). + +Extended status interval (µs) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000000 | | 50000 | us | + +### int_status (`INT32`) {#int_status} + +ESC status interval (µs). + +ESC status interval (µs) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | 1000000 | | 50000 | us | + +### mot_i_max (`FLOAT`) {#mot_i_max} + +Motor current limit in amps. + +This determines the maximum +current controller setpoint, as well as the maximum allowable +current setpoint slew rate. This value should generally be set to +the continuous current rating listed in the motor’s specification +sheet, or set equal to the motor’s specified continuous power +divided by the motor voltage limit. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 80 | | 12 | A | + +### mot_kv (`INT32`) {#mot_kv} + +Motor Kv in RPM per volt. + +This can be taken from the motor’s +specification sheet; accuracy will help control performance but +some deviation from the specified value is acceptable. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | 0 | 4000 | | 2300 | rpm/V | + +### mot_ls (`FLOAT`) {#mot_ls} + +READ ONLY: Motor inductance in henries. + +This is measured on start-up. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | H | + +### mot_num_poles (`INT32`) {#mot_num_poles} + +Number of motor poles. + +Used to convert mechanical speeds to +electrical speeds. This number should be taken from the motor’s +specification sheet. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 2 | 40 | | 14 | + +### mot_rs (`FLOAT`) {#mot_rs} + +READ ONLY: Motor resistance in ohms. + +This is measured on start-up. When +tuning a new motor, check that this value is approximately equal +to the value shown in the motor’s specification sheet. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | Ohm | + +### mot_v_accel (`FLOAT`) {#mot_v_accel} + +Acceleration limit (V). + +Acceleration limit (V) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.01 | 1.00 | | 0.5 | V | + +### mot_v_max (`FLOAT`) {#mot_v_max} + +Motor voltage limit in volts. + +The current controller’s +commanded voltage will never exceed this value. Note that this may +safely be above the nominal voltage of the motor; to determine the +actual motor voltage limit, divide the motor’s rated power by the +motor current limit. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | | | 14.8 | V | + +## UAVCAN GNSS + +### gnss.dyn_model (`INT32`) {#gnss.dyn_model} + +GNSS dynamic model. + +Dynamic model used in the GNSS positioning engine. 0 – +Automotive, 1 – Sea, 2 – Airborne. + +**Values:** + +- `0`: Automotive +- `1`: Sea +- `2`: Airborne + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 2 | | 2 | + +### gnss.old_fix_msg (`INT32`) {#gnss.old_fix_msg} + +Broadcast old GNSS fix message. + +Broadcast the old (deprecated) GNSS fix message +uavcan.equipment.gnss.Fix alongside the new alternative +uavcan.equipment.gnss.Fix2. It is recommended to +disable this feature to reduce the CAN bus traffic. + +**Values:** + +- `0`: Fix2 +- `1`: Fix and Fix2 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | | 1 | + +### gnss.warn_dimens (`INT32`) {#gnss.warn_dimens} + +device health warning. + +Set the device health to Warning if the dimensionality of +the GNSS solution is less than this value. 3 for the full (3D) +solution, 2 for planar (2D) solution, 1 for time-only solution, +0 disables the feature. + +**Values:** + +- `0`: disables the feature +- `1`: time-only solution +- `2`: planar (2D) solution +- `3`: full (3D) solution + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 3 | | 0 | + +### gnss.warn_sats (`INT32`) {#gnss.warn_sats} + +Set the device health to Warning if the number of satellites +used in the GNSS solution is below this threshold. Zero +disables the feature + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + +### uavcan.pubp-pres (`INT32`) {#uavcan.pubp-pres} + +Set the device health to Warning if the number of satellites +used in the GNSS solution is below this threshold. Zero +disables the feature + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000000 | | 0 | us | ## ADSB @@ -58,8 +274,7 @@ The voltage applied to the TLA2528 board as reference First 4 characters of CALLSIGN. -Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, " ". Example "PX4 " -> 1347957792 -For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. +Sets first 4 characters of a total of 8. Valid characters are A-Z, 0-9, " ". Example "PX4 " -> 1347957792 For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -69,8 +284,7 @@ For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. Second 4 characters of CALLSIGN. -Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, " " only. Example "TEST" -> 1413829460 -For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. +Sets second 4 characters of a total of 8. Valid characters are A-Z, 0-9, " " only. Example "TEST" -> 1413829460 For CALLSIGN shorter than 8 characters use the null terminator at the end '\0'. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -270,8 +484,7 @@ This parameter defines the squawk code. Value should be between 0000 and 7777. PCA9685 Output Channel 1 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -281,8 +494,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 10 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -292,8 +504,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 11 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -303,8 +514,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 12 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -314,8 +524,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 13 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -325,8 +534,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 14 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -336,8 +544,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 15 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -347,8 +554,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 16 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -358,8 +564,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 2 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -369,8 +574,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 3 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -380,8 +584,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 4 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -391,8 +594,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 5 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -402,8 +604,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 6 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -413,8 +614,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 7 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -424,8 +624,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 8 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -435,8 +634,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PCA9685 Output Channel 9 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -446,12 +644,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR Put the selected channels into Duty-Cycle output mode. -The driver will output standard pulse-width encoded signal without this bit set. -To make PCA9685 output in duty-cycle fashion, please enable the corresponding -channel bit here and adjusting standard params to suit your need. -The driver will have 12bits resolution for duty-cycle output. That means to achieve 0% to 100% -output range on one channel, the corresponding params MIN and MAX for the channel should be set -to 0 and 4096. Other standard params follows the same rule. +The driver will output standard pulse-width encoded signal without this bit set. To make PCA9685 output in duty-cycle fashion, please enable the corresponding channel bit here and adjusting standard params to suit your need. The driver will have 12bits resolution for duty-cycle output. That means to achieve 0% to 100% output range on one channel, the corresponding params MIN and MAX for the channel should be set to 0 and 4096. Other standard params follows the same rule. **Bitmask:** @@ -476,22 +669,11 @@ to 0 and 4096. Other standard params follows the same rule. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 65535 | | 0 | -### PCA9685_EN_BUS (`INT32`) {#PCA9685_EN_BUS} - -Enable the PCA9685 output driver. - -The integer refers to the I2C bus number where PCA9685 is connected. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 10 | | 0 | - ### PCA9685_FAIL1 (`INT32`) {#PCA9685_FAIL1} PCA9685 Output Channel 1 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -501,8 +683,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC1). PCA9685 Output Channel 10 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC10). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC10). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -512,8 +693,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC10) PCA9685 Output Channel 11 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC11). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC11). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -523,8 +703,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC11) PCA9685 Output Channel 12 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC12). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC12). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -534,8 +713,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC12) PCA9685 Output Channel 13 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC13). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC13). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -545,8 +723,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC13) PCA9685 Output Channel 14 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC14). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC14). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -556,8 +733,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC14) PCA9685 Output Channel 15 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC15). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC15). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -567,8 +743,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC15) PCA9685 Output Channel 16 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC16). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC16). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -578,8 +753,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC16) PCA9685 Output Channel 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -589,8 +763,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC2). PCA9685 Output Channel 3 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC3). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -600,8 +773,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC3). PCA9685 Output Channel 4 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC4). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -611,8 +783,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC4). PCA9685 Output Channel 5 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC5). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC5). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -622,8 +793,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC5). PCA9685 Output Channel 6 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC6). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -633,8 +803,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC6). PCA9685 Output Channel 7 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC7). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC7). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -644,8 +813,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC7). PCA9685 Output Channel 8 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC8). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC8). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -655,8 +823,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC8). PCA9685 Output Channel 9 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PCA9685_FUNC9). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PCA9685_FUNC9). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -666,14 +833,7 @@ When set to -1 (default), the value depends on the function (see PCA9685_FUNC9). PCA9685 Output Channel 1 Output Function. -Select what should be output on PCA9685 Output Channel 1. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -737,14 +897,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 10 Output Function. -Select what should be output on PCA9685 Output Channel 10. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -808,14 +961,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 11 Output Function. -Select what should be output on PCA9685 Output Channel 11. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -879,14 +1025,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 12 Output Function. -Select what should be output on PCA9685 Output Channel 12. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -950,14 +1089,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 13 Output Function. -Select what should be output on PCA9685 Output Channel 13. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1021,14 +1153,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 14 Output Function. -Select what should be output on PCA9685 Output Channel 14. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1092,14 +1217,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 15 Output Function. -Select what should be output on PCA9685 Output Channel 15. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1163,14 +1281,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 16 Output Function. -Select what should be output on PCA9685 Output Channel 16. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 16. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1234,14 +1345,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 2 Output Function. -Select what should be output on PCA9685 Output Channel 2. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1305,14 +1409,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 3 Output Function. -Select what should be output on PCA9685 Output Channel 3. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1376,14 +1473,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 4 Output Function. -Select what should be output on PCA9685 Output Channel 4. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1447,14 +1537,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 5 Output Function. -Select what should be output on PCA9685 Output Channel 5. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1518,14 +1601,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 6 Output Function. -Select what should be output on PCA9685 Output Channel 6. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1589,14 +1665,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 7 Output Function. -Select what should be output on PCA9685 Output Channel 7. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1660,14 +1729,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 8 Output Function. -Select what should be output on PCA9685 Output Channel 8. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1731,14 +1793,7 @@ The default failsafe value is set according to the selected function: PCA9685 Output Channel 9 Output Function. -Select what should be output on PCA9685 Output Channel 9. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PCA9685 Output Channel 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -1798,16 +1853,6 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### PCA9685_I2C_ADDR (`INT32`) {#PCA9685_I2C_ADDR} - -I2C address of PCA9685. - -The default address is 0x40 (64). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 127 | | 64 | - ### PCA9685_MAX1 (`INT32`) {#PCA9685_MAX1} PCA9685 Output Channel 1 Maximum Value. @@ -2132,13 +2177,7 @@ Minimum output value (when not disarmed). PWM cycle frequency. -Controls the PWM frequency at timing perspective. -This is independent from PWM update frequency, as PCA9685 is capable to output -without being continuously commanded by FC. -Higher frequency leads to more accurate pulse width, but some ESCs and servos may not support it. -This parameter should be set to the same value as PWM update rate in most case. -This parameter MUST NOT exceed upper limit of 400.0, if any outputs as generic 1000~2000us -pulse width is desired. Frequency higher than 400 only makes sense in duty-cycle mode. +Controls the PWM frequency at timing perspective. This is independent from PWM update frequency, as PCA9685 is capable to output without being continuously commanded by FC. Higher frequency leads to more accurate pulse width, but some ESCs and servos may not support it. This parameter should be set to the same value as PWM update rate in most case. This parameter MUST NOT exceed upper limit of 400.0, if any outputs as generic 1000~2000us pulse width is desired. Frequency higher than 400 only makes sense in duty-cycle mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2148,8 +2187,7 @@ pulse width is desired. Frequency higher than 400 only makes sense in duty-cycle Reverse Output Range for PCA9685 Output. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** @@ -2178,131 +2216,17 @@ Note: this is only useful for servos. PWM update rate. -Controls the update rate of PWM output. -Flight Controller will inform those numbers of update events in a second, to PCA9685. -Higher update rate will consume more I2C bandwidth, which may even lead to worse -output latency, or completely block I2C bus. +Controls the update rate of PWM output. Flight Controller will inform those numbers of update events in a second, to PCA9685. Higher update rate will consume more I2C bandwidth, which may even lead to worse output latency, or completely block I2C bus. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 50.0 | 400.0 | | 50.0 | -### PWM_AUX_CENT1 (`INT32`) {#PWM_AUX_CENT1} - -PWM Aux 1 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT10 (`INT32`) {#PWM_AUX_CENT10} - -PWM Capture 2 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT11 (`INT32`) {#PWM_AUX_CENT11} - -PWM Capture 3 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT2 (`INT32`) {#PWM_AUX_CENT2} - -PWM Aux 2 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT3 (`INT32`) {#PWM_AUX_CENT3} - -PWM Aux 3 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT4 (`INT32`) {#PWM_AUX_CENT4} - -PWM Aux 4 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT5 (`INT32`) {#PWM_AUX_CENT5} - -PWM Aux 5 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT6 (`INT32`) {#PWM_AUX_CENT6} - -PWM Aux 6 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT7 (`INT32`) {#PWM_AUX_CENT7} - -PWM Aux 7 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT8 (`INT32`) {#PWM_AUX_CENT8} - -PWM Aux 8 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - -### PWM_AUX_CENT9 (`INT32`) {#PWM_AUX_CENT9} - -PWM Capture 1 Center Value. - -Servo Center output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 2200 | | -1 | - ### PWM_AUX_DIS1 (`INT32`) {#PWM_AUX_DIS1} PWM Aux 1 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2312,8 +2236,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Capture 2 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2323,8 +2246,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Capture 3 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2334,8 +2256,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 2 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2345,8 +2266,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 3 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2356,8 +2276,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 4 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2367,8 +2286,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 5 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2378,8 +2296,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 6 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2389,8 +2306,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 7 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2400,8 +2316,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 8 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2411,8 +2326,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Capture 1 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2422,8 +2336,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR PWM Aux 1 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2433,8 +2346,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC1). PWM Capture 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2444,8 +2356,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC2). PWM Capture 3 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC3). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2455,8 +2366,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC3). PWM Aux 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2466,8 +2376,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC2). PWM Aux 3 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC3). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2477,8 +2386,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC3). PWM Aux 4 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC4). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2488,8 +2396,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC4). PWM Aux 5 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC5). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC5). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2499,8 +2406,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC5). PWM Aux 6 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC6). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2510,8 +2416,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC6). PWM Aux 7 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC7). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC7). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2521,8 +2426,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC7). PWM Aux 8 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC8). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC8). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2532,8 +2436,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC8). PWM Capture 1 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -2543,14 +2446,7 @@ When set to -1 (default), the value depends on the function (see PWM_AUX_FUNC1). PWM Aux 1 Output Function. -Select what should be output on PWM Aux 1. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -2618,14 +2514,7 @@ The default failsafe value is set according to the selected function: PWM Capture 2 Output Function. -Select what should be output on PWM Capture 2. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Capture 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -2693,14 +2582,7 @@ The default failsafe value is set according to the selected function: PWM Capture 3 Output Function. -Select what should be output on PWM Capture 3. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Capture 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -2768,14 +2650,7 @@ The default failsafe value is set according to the selected function: PWM Aux 2 Output Function. -Select what should be output on PWM Aux 2. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -2843,14 +2718,7 @@ The default failsafe value is set according to the selected function: PWM Aux 3 Output Function. -Select what should be output on PWM Aux 3. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -2918,14 +2786,7 @@ The default failsafe value is set according to the selected function: PWM Aux 4 Output Function. -Select what should be output on PWM Aux 4. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -2993,14 +2854,7 @@ The default failsafe value is set according to the selected function: PWM Aux 5 Output Function. -Select what should be output on PWM Aux 5. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -3068,14 +2922,7 @@ The default failsafe value is set according to the selected function: PWM Aux 6 Output Function. -Select what should be output on PWM Aux 6. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -3143,14 +2990,7 @@ The default failsafe value is set according to the selected function: PWM Aux 7 Output Function. -Select what should be output on PWM Aux 7. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -3218,14 +3058,7 @@ The default failsafe value is set according to the selected function: PWM Aux 8 Output Function. -Select what should be output on PWM Aux 8. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Aux 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -3293,14 +3126,7 @@ The default failsafe value is set according to the selected function: PWM Capture 1 Output Function. -Select what should be output on PWM Capture 1. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on PWM Capture 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -3588,8 +3414,7 @@ Minimum output value (when not disarmed). Reverse Output Range for PWM AUX. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** @@ -3613,8 +3438,7 @@ Note: this is only useful for servos. Output Protocol Configuration for PWM Aux 1-4. -Select which Output Protocol to use for outputs PWM Aux 1-4. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs PWM Aux 1-4. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -3635,8 +3459,7 @@ Custom PWM rates can be used by directly setting any value >0. Output Protocol Configuration for PWM Aux 5-6. -Select which Output Protocol to use for outputs PWM Aux 5-6. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs PWM Aux 5-6. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -3654,8 +3477,7 @@ Custom PWM rates can be used by directly setting any value >0. Output Protocol Configuration for PWM Aux 7-8. -Select which Output Protocol to use for outputs PWM Aux 7-8. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs PWM Aux 7-8. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -3673,8 +3495,7 @@ Custom PWM rates can be used by directly setting any value >0. Output Protocol Configuration for PWM Capture 1-3. -Select which Output Protocol to use for outputs PWM Capture 1-3. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs PWM Capture 1-3. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -3692,8 +3513,7 @@ Custom PWM rates can be used by directly setting any value >0. MAIN 1 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3703,8 +3523,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 2 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3714,8 +3533,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 3 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3725,8 +3543,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 4 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3736,8 +3553,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 5 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3747,8 +3563,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 6 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3758,8 +3573,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 7 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3769,8 +3583,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 8 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3780,8 +3593,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR MAIN 1 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3791,8 +3603,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC1) MAIN 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3802,8 +3613,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC2) MAIN 3 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC3). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3813,8 +3623,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC3) MAIN 4 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC4). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3824,8 +3633,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC4) MAIN 5 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC5). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC5). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3835,8 +3643,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC5) MAIN 6 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC6). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3846,8 +3653,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC6) MAIN 7 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC7). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC7). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3857,8 +3663,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC7) MAIN 8 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC8). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC8). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -3868,14 +3673,7 @@ When set to -1 (default), the value depends on the function (see PWM_MAIN_FUNC8) MAIN 1 Output Function. -Select what should be output on MAIN 1. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -3939,14 +3737,7 @@ The default failsafe value is set according to the selected function: MAIN 2 Output Function. -Select what should be output on MAIN 2. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4010,14 +3801,7 @@ The default failsafe value is set according to the selected function: MAIN 3 Output Function. -Select what should be output on MAIN 3. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4081,14 +3865,7 @@ The default failsafe value is set according to the selected function: MAIN 4 Output Function. -Select what should be output on MAIN 4. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4152,14 +3929,7 @@ The default failsafe value is set according to the selected function: MAIN 5 Output Function. -Select what should be output on MAIN 5. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4223,14 +3993,7 @@ The default failsafe value is set according to the selected function: MAIN 6 Output Function. -Select what should be output on MAIN 6. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4294,14 +4057,7 @@ The default failsafe value is set according to the selected function: MAIN 7 Output Function. -Select what should be output on MAIN 7. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4365,14 +4121,7 @@ The default failsafe value is set according to the selected function: MAIN 8 Output Function. -Select what should be output on MAIN 8. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on MAIN 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4596,8 +4345,7 @@ Minimum output value (when not disarmed). Reverse Output Range for PWM MAIN. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** @@ -4618,8 +4366,7 @@ Note: this is only useful for servos. Output Protocol Configuration for MAIN 1-2. -Select which Output Protocol to use for outputs MAIN 1-2. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs MAIN 1-2. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -4637,8 +4384,7 @@ Custom PWM rates can be used by directly setting any value >0. Output Protocol Configuration for MAIN 3-4. -Select which Output Protocol to use for outputs MAIN 3-4. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs MAIN 3-4. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -4656,8 +4402,7 @@ Custom PWM rates can be used by directly setting any value >0. Output Protocol Configuration for MAIN 5-8. -Select which Output Protocol to use for outputs MAIN 5-8. -Custom PWM rates can be used by directly setting any value >0. +Select which Output Protocol to use for outputs MAIN 5-8. Custom PWM rates can be used by directly setting any value >0. **Values:** @@ -4675,8 +4420,7 @@ Custom PWM rates can be used by directly setting any value >0. Roboclaw Driver Channel 1 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4686,8 +4430,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR Roboclaw Driver Channel 2 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4697,8 +4440,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR Roboclaw Driver Channel 1 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see RBCLW_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see RBCLW_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4708,8 +4450,7 @@ When set to -1 (default), the value depends on the function (see RBCLW_FUNC1). Roboclaw Driver Channel 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see RBCLW_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see RBCLW_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4719,14 +4460,7 @@ When set to -1 (default), the value depends on the function (see RBCLW_FUNC2). Roboclaw Driver Channel 1 Output Function. -Select what should be output on Roboclaw Driver Channel 1. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Roboclaw Driver Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4790,14 +4524,7 @@ The default failsafe value is set according to the selected function: Roboclaw Driver Channel 2 Output Function. -Select what should be output on Roboclaw Driver Channel 2. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Roboclaw Driver Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -4901,8 +4628,7 @@ Minimum output value (when not disarmed). Reverse Output Range for Roboclaw Driver. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** @@ -4917,41 +4643,7 @@ Note: this is only useful for servos. SIM_GZ ESC 1 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_EC_DIS10 (`INT32`) {#SIM_GZ_EC_DIS10} - -SIM_GZ ESC 10 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_EC_DIS11 (`INT32`) {#SIM_GZ_EC_DIS11} - -SIM_GZ ESC 11 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_EC_DIS12 (`INT32`) {#SIM_GZ_EC_DIS12} - -SIM_GZ ESC 12 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4961,8 +4653,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 2 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4972,8 +4663,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 3 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4983,8 +4673,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 4 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -4994,8 +4683,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 5 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -5005,8 +4693,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 6 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -5016,8 +4703,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 7 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -5027,19 +4713,7 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 8 Disarmed Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_EC_DIS9 (`INT32`) {#SIM_GZ_EC_DIS9} - -SIM_GZ ESC 9 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -5049,146 +4723,343 @@ Note that non-motor outputs might already be active in prearm state if COM_PREAR SIM_GZ ESC 1 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL10 (`INT32`) {#SIM_GZ_EC_FAIL10} +### SIM_GZ_EC_FAIL2 (`INT32`) {#SIM_GZ_EC_FAIL2} -SIM_GZ ESC 10 Failsafe Value. +SIM_GZ ESC 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC10). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL11 (`INT32`) {#SIM_GZ_EC_FAIL11} +### SIM_GZ_EC_FAIL3 (`INT32`) {#SIM_GZ_EC_FAIL3} -SIM_GZ ESC 11 Failsafe Value. +SIM_GZ ESC 3 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC11). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL12 (`INT32`) {#SIM_GZ_EC_FAIL12} +### SIM_GZ_EC_FAIL4 (`INT32`) {#SIM_GZ_EC_FAIL4} -SIM_GZ ESC 12 Failsafe Value. +SIM_GZ ESC 4 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC12). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL2 (`INT32`) {#SIM_GZ_EC_FAIL2} +### SIM_GZ_EC_FAIL5 (`INT32`) {#SIM_GZ_EC_FAIL5} -SIM_GZ ESC 2 Failsafe Value. +SIM_GZ ESC 5 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC5). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL3 (`INT32`) {#SIM_GZ_EC_FAIL3} +### SIM_GZ_EC_FAIL6 (`INT32`) {#SIM_GZ_EC_FAIL6} -SIM_GZ ESC 3 Failsafe Value. +SIM_GZ ESC 6 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC3). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL4 (`INT32`) {#SIM_GZ_EC_FAIL4} +### SIM_GZ_EC_FAIL7 (`INT32`) {#SIM_GZ_EC_FAIL7} -SIM_GZ ESC 4 Failsafe Value. +SIM_GZ ESC 7 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC4). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC7). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL5 (`INT32`) {#SIM_GZ_EC_FAIL5} +### SIM_GZ_EC_FAIL8 (`INT32`) {#SIM_GZ_EC_FAIL8} -SIM_GZ ESC 5 Failsafe Value. +SIM_GZ ESC 8 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC5). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC8). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | -1 | 1000 | | -1 | -### SIM_GZ_EC_FAIL6 (`INT32`) {#SIM_GZ_EC_FAIL6} +### SIM_GZ_EC_FUNC1 (`INT32`) {#SIM_GZ_EC_FUNC1} -SIM_GZ ESC 6 Failsafe Value. +SIM_GZ ESC 1 Output Function. + +Select what should be output on SIM_GZ ESC 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC6). +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | | | | 0 | -### SIM_GZ_EC_FAIL7 (`INT32`) {#SIM_GZ_EC_FAIL7} +### SIM_GZ_EC_FUNC2 (`INT32`) {#SIM_GZ_EC_FUNC2} -SIM_GZ ESC 7 Failsafe Value. +SIM_GZ ESC 2 Output Function. + +Select what should be output on SIM_GZ ESC 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC7). +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | | | | 0 | -### SIM_GZ_EC_FAIL8 (`INT32`) {#SIM_GZ_EC_FAIL8} +### SIM_GZ_EC_FUNC3 (`INT32`) {#SIM_GZ_EC_FUNC3} -SIM_GZ ESC 8 Failsafe Value. +SIM_GZ ESC 3 Output Function. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC8). +Select what should be output on SIM_GZ ESC 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | | | | 0 | + +### SIM_GZ_EC_FUNC4 (`INT32`) {#SIM_GZ_EC_FUNC4} -### SIM_GZ_EC_FAIL9 (`INT32`) {#SIM_GZ_EC_FAIL9} +SIM_GZ ESC 4 Output Function. -SIM_GZ ESC 9 Failsafe Value. +Select what should be output on SIM_GZ ESC 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_EC_FUNC9). +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_EC_FUNC1 (`INT32`) {#SIM_GZ_EC_FUNC1} +|   | | | | 0 | -SIM_GZ ESC 1 Output Function. +### SIM_GZ_EC_FUNC5 (`INT32`) {#SIM_GZ_EC_FUNC5} -Select what should be output on SIM_GZ ESC 1. -The default failsafe value is set according to the selected function: +SIM_GZ ESC 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ ESC 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5248,18 +5119,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC10 (`INT32`) {#SIM_GZ_EC_FUNC10} - -SIM_GZ ESC 10 Output Function. +### SIM_GZ_EC_FUNC6 (`INT32`) {#SIM_GZ_EC_FUNC6} -Select what should be output on SIM_GZ ESC 10. -The default failsafe value is set according to the selected function: +SIM_GZ ESC 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ ESC 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5319,18 +5183,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC11 (`INT32`) {#SIM_GZ_EC_FUNC11} - -SIM_GZ ESC 11 Output Function. +### SIM_GZ_EC_FUNC7 (`INT32`) {#SIM_GZ_EC_FUNC7} -Select what should be output on SIM_GZ ESC 11. -The default failsafe value is set according to the selected function: +SIM_GZ ESC 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ ESC 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5390,18 +5247,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC12 (`INT32`) {#SIM_GZ_EC_FUNC12} - -SIM_GZ ESC 12 Output Function. +### SIM_GZ_EC_FUNC8 (`INT32`) {#SIM_GZ_EC_FUNC8} -Select what should be output on SIM_GZ ESC 12. -The default failsafe value is set according to the selected function: +SIM_GZ ESC 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ ESC 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5461,18 +5311,352 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC2 (`INT32`) {#SIM_GZ_EC_FUNC2} +### SIM_GZ_EC_MAX1 (`INT32`) {#SIM_GZ_EC_MAX1} -SIM_GZ ESC 2 Output Function. +SIM_GZ ESC 1 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX2 (`INT32`) {#SIM_GZ_EC_MAX2} + +SIM_GZ ESC 2 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX3 (`INT32`) {#SIM_GZ_EC_MAX3} + +SIM_GZ ESC 3 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX4 (`INT32`) {#SIM_GZ_EC_MAX4} + +SIM_GZ ESC 4 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX5 (`INT32`) {#SIM_GZ_EC_MAX5} + +SIM_GZ ESC 5 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX6 (`INT32`) {#SIM_GZ_EC_MAX6} + +SIM_GZ ESC 6 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX7 (`INT32`) {#SIM_GZ_EC_MAX7} + +SIM_GZ ESC 7 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MAX8 (`INT32`) {#SIM_GZ_EC_MAX8} + +SIM_GZ ESC 8 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 1000 | + +### SIM_GZ_EC_MIN1 (`INT32`) {#SIM_GZ_EC_MIN1} + +SIM_GZ ESC 1 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN2 (`INT32`) {#SIM_GZ_EC_MIN2} + +SIM_GZ ESC 2 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN3 (`INT32`) {#SIM_GZ_EC_MIN3} + +SIM_GZ ESC 3 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN4 (`INT32`) {#SIM_GZ_EC_MIN4} + +SIM_GZ ESC 4 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN5 (`INT32`) {#SIM_GZ_EC_MIN5} + +SIM_GZ ESC 5 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN6 (`INT32`) {#SIM_GZ_EC_MIN6} + +SIM_GZ ESC 6 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN7 (`INT32`) {#SIM_GZ_EC_MIN7} + +SIM_GZ ESC 7 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_MIN8 (`INT32`) {#SIM_GZ_EC_MIN8} + +SIM_GZ ESC 8 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 0 | + +### SIM_GZ_EC_REV (`INT32`) {#SIM_GZ_EC_REV} + +Reverse Output Range for SIM_GZ. + +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: SIM_GZ ESC 1 +- `1`: SIM_GZ ESC 2 +- `2`: SIM_GZ ESC 3 +- `3`: SIM_GZ ESC 4 +- `4`: SIM_GZ ESC 5 +- `5`: SIM_GZ ESC 6 +- `6`: SIM_GZ ESC 7 +- `7`: SIM_GZ ESC 8 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 255 | | 0 | + +### SIM_GZ_SV_DIS1 (`INT32`) {#SIM_GZ_SV_DIS1} + +SIM_GZ Servo 1 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS2 (`INT32`) {#SIM_GZ_SV_DIS2} + +SIM_GZ Servo 2 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS3 (`INT32`) {#SIM_GZ_SV_DIS3} + +SIM_GZ Servo 3 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS4 (`INT32`) {#SIM_GZ_SV_DIS4} + +SIM_GZ Servo 4 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS5 (`INT32`) {#SIM_GZ_SV_DIS5} + +SIM_GZ Servo 5 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS6 (`INT32`) {#SIM_GZ_SV_DIS6} + +SIM_GZ Servo 6 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS7 (`INT32`) {#SIM_GZ_SV_DIS7} + +SIM_GZ Servo 7 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_DIS8 (`INT32`) {#SIM_GZ_SV_DIS8} + +SIM_GZ Servo 8 Disarmed Value. + +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1000 | | 500 | + +### SIM_GZ_SV_FAIL1 (`INT32`) {#SIM_GZ_SV_FAIL1} + +SIM_GZ Servo 1 Failsafe Value. -Select what should be output on SIM_GZ ESC 2. -The default failsafe value is set according to the selected function: +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC1). -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL2 (`INT32`) {#SIM_GZ_SV_FAIL2} + +SIM_GZ Servo 2 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC2). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL3 (`INT32`) {#SIM_GZ_SV_FAIL3} + +SIM_GZ Servo 3 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC3). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL4 (`INT32`) {#SIM_GZ_SV_FAIL4} + +SIM_GZ Servo 4 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC4). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL5 (`INT32`) {#SIM_GZ_SV_FAIL5} + +SIM_GZ Servo 5 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC5). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL6 (`INT32`) {#SIM_GZ_SV_FAIL6} + +SIM_GZ Servo 6 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC6). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL7 (`INT32`) {#SIM_GZ_SV_FAIL7} + +SIM_GZ Servo 7 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC7). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FAIL8 (`INT32`) {#SIM_GZ_SV_FAIL8} + +SIM_GZ Servo 8 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC8). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### SIM_GZ_SV_FUNC1 (`INT32`) {#SIM_GZ_SV_FUNC1} + +SIM_GZ Servo 1 Output Function. + +Select what should be output on SIM_GZ Servo 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5532,18 +5716,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC3 (`INT32`) {#SIM_GZ_EC_FUNC3} - -SIM_GZ ESC 3 Output Function. +### SIM_GZ_SV_FUNC2 (`INT32`) {#SIM_GZ_SV_FUNC2} -Select what should be output on SIM_GZ ESC 3. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5603,18 +5780,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC4 (`INT32`) {#SIM_GZ_EC_FUNC4} - -SIM_GZ ESC 4 Output Function. +### SIM_GZ_SV_FUNC3 (`INT32`) {#SIM_GZ_SV_FUNC3} -Select what should be output on SIM_GZ ESC 4. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5674,18 +5844,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC5 (`INT32`) {#SIM_GZ_EC_FUNC5} - -SIM_GZ ESC 5 Output Function. +### SIM_GZ_SV_FUNC4 (`INT32`) {#SIM_GZ_SV_FUNC4} -Select what should be output on SIM_GZ ESC 5. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5745,18 +5908,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC6 (`INT32`) {#SIM_GZ_EC_FUNC6} - -SIM_GZ ESC 6 Output Function. +### SIM_GZ_SV_FUNC5 (`INT32`) {#SIM_GZ_SV_FUNC5} -Select what should be output on SIM_GZ ESC 6. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5816,18 +5972,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC7 (`INT32`) {#SIM_GZ_EC_FUNC7} - -SIM_GZ ESC 7 Output Function. +### SIM_GZ_SV_FUNC6 (`INT32`) {#SIM_GZ_SV_FUNC6} -Select what should be output on SIM_GZ ESC 7. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5887,18 +6036,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC8 (`INT32`) {#SIM_GZ_EC_FUNC8} - -SIM_GZ ESC 8 Output Function. +### SIM_GZ_SV_FUNC7 (`INT32`) {#SIM_GZ_SV_FUNC7} -Select what should be output on SIM_GZ ESC 8. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -5958,18 +6100,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_FUNC9 (`INT32`) {#SIM_GZ_EC_FUNC9} - -SIM_GZ ESC 9 Output Function. +### SIM_GZ_SV_FUNC8 (`INT32`) {#SIM_GZ_SV_FUNC8} -Select what should be output on SIM_GZ ESC 9. -The default failsafe value is set according to the selected function: +SIM_GZ Servo 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Servo 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6029,9 +6164,9 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_EC_MAX1 (`INT32`) {#SIM_GZ_EC_MAX1} +### SIM_GZ_SV_MAX1 (`INT32`) {#SIM_GZ_SV_MAX1} -SIM_GZ ESC 1 Maximum Value. +SIM_GZ Servo 1 Maximum Value. Maxmimum output value (when not disarmed). @@ -6039,9 +6174,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX10 (`INT32`) {#SIM_GZ_EC_MAX10} +### SIM_GZ_SV_MAX2 (`INT32`) {#SIM_GZ_SV_MAX2} -SIM_GZ ESC 10 Maximum Value. +SIM_GZ Servo 2 Maximum Value. Maxmimum output value (when not disarmed). @@ -6049,9 +6184,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX11 (`INT32`) {#SIM_GZ_EC_MAX11} +### SIM_GZ_SV_MAX3 (`INT32`) {#SIM_GZ_SV_MAX3} -SIM_GZ ESC 11 Maximum Value. +SIM_GZ Servo 3 Maximum Value. Maxmimum output value (when not disarmed). @@ -6059,9 +6194,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX12 (`INT32`) {#SIM_GZ_EC_MAX12} +### SIM_GZ_SV_MAX4 (`INT32`) {#SIM_GZ_SV_MAX4} -SIM_GZ ESC 12 Maximum Value. +SIM_GZ Servo 4 Maximum Value. Maxmimum output value (when not disarmed). @@ -6069,9 +6204,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX2 (`INT32`) {#SIM_GZ_EC_MAX2} +### SIM_GZ_SV_MAX5 (`INT32`) {#SIM_GZ_SV_MAX5} -SIM_GZ ESC 2 Maximum Value. +SIM_GZ Servo 5 Maximum Value. Maxmimum output value (when not disarmed). @@ -6079,9 +6214,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX3 (`INT32`) {#SIM_GZ_EC_MAX3} +### SIM_GZ_SV_MAX6 (`INT32`) {#SIM_GZ_SV_MAX6} -SIM_GZ ESC 3 Maximum Value. +SIM_GZ Servo 6 Maximum Value. Maxmimum output value (when not disarmed). @@ -6089,9 +6224,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX4 (`INT32`) {#SIM_GZ_EC_MAX4} +### SIM_GZ_SV_MAX7 (`INT32`) {#SIM_GZ_SV_MAX7} -SIM_GZ ESC 4 Maximum Value. +SIM_GZ Servo 7 Maximum Value. Maxmimum output value (when not disarmed). @@ -6099,9 +6234,9 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX5 (`INT32`) {#SIM_GZ_EC_MAX5} +### SIM_GZ_SV_MAX8 (`INT32`) {#SIM_GZ_SV_MAX8} -SIM_GZ ESC 5 Maximum Value. +SIM_GZ Servo 8 Maximum Value. Maxmimum output value (when not disarmed). @@ -6109,49 +6244,49 @@ Maxmimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 1000 | -### SIM_GZ_EC_MAX6 (`INT32`) {#SIM_GZ_EC_MAX6} +### SIM_GZ_SV_MIN1 (`INT32`) {#SIM_GZ_SV_MIN1} -SIM_GZ ESC 6 Maximum Value. +SIM_GZ Servo 1 Minimum Value. -Maxmimum output value (when not disarmed). +Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | +|   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MAX7 (`INT32`) {#SIM_GZ_EC_MAX7} +### SIM_GZ_SV_MIN2 (`INT32`) {#SIM_GZ_SV_MIN2} -SIM_GZ ESC 7 Maximum Value. +SIM_GZ Servo 2 Minimum Value. -Maxmimum output value (when not disarmed). +Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | +|   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MAX8 (`INT32`) {#SIM_GZ_EC_MAX8} +### SIM_GZ_SV_MIN3 (`INT32`) {#SIM_GZ_SV_MIN3} -SIM_GZ ESC 8 Maximum Value. +SIM_GZ Servo 3 Minimum Value. -Maxmimum output value (when not disarmed). +Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | +|   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MAX9 (`INT32`) {#SIM_GZ_EC_MAX9} +### SIM_GZ_SV_MIN4 (`INT32`) {#SIM_GZ_SV_MIN4} -SIM_GZ ESC 9 Maximum Value. +SIM_GZ Servo 4 Minimum Value. -Maxmimum output value (when not disarmed). +Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | +|   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MIN1 (`INT32`) {#SIM_GZ_EC_MIN1} +### SIM_GZ_SV_MIN5 (`INT32`) {#SIM_GZ_SV_MIN5} -SIM_GZ ESC 1 Minimum Value. +SIM_GZ Servo 5 Minimum Value. Minimum output value (when not disarmed). @@ -6159,9 +6294,9 @@ Minimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MIN10 (`INT32`) {#SIM_GZ_EC_MIN10} +### SIM_GZ_SV_MIN6 (`INT32`) {#SIM_GZ_SV_MIN6} -SIM_GZ ESC 10 Minimum Value. +SIM_GZ Servo 6 Minimum Value. Minimum output value (when not disarmed). @@ -6169,9 +6304,9 @@ Minimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MIN11 (`INT32`) {#SIM_GZ_EC_MIN11} +### SIM_GZ_SV_MIN7 (`INT32`) {#SIM_GZ_SV_MIN7} -SIM_GZ ESC 11 Minimum Value. +SIM_GZ Servo 7 Minimum Value. Minimum output value (when not disarmed). @@ -6179,9 +6314,9 @@ Minimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MIN12 (`INT32`) {#SIM_GZ_EC_MIN12} +### SIM_GZ_SV_MIN8 (`INT32`) {#SIM_GZ_SV_MIN8} -SIM_GZ ESC 12 Minimum Value. +SIM_GZ Servo 8 Minimum Value. Minimum output value (when not disarmed). @@ -6189,300 +6324,112 @@ Minimum output value (when not disarmed). | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1000 | | 0 | -### SIM_GZ_EC_MIN2 (`INT32`) {#SIM_GZ_EC_MIN2} +### SIM_GZ_SV_REV (`INT32`) {#SIM_GZ_SV_REV} -SIM_GZ ESC 2 Minimum Value. +Reverse Output Range for SIM_GZ. -Minimum output value (when not disarmed). +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: SIM_GZ Servo 1 +- `1`: SIM_GZ Servo 2 +- `2`: SIM_GZ Servo 3 +- `3`: SIM_GZ Servo 4 +- `4`: SIM_GZ Servo 5 +- `5`: SIM_GZ Servo 6 +- `6`: SIM_GZ Servo 7 +- `7`: SIM_GZ Servo 8 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | 0 | 255 | | 0 | -### SIM_GZ_EC_MIN3 (`INT32`) {#SIM_GZ_EC_MIN3} +### SIM_GZ_WH_DIS1 (`INT32`) {#SIM_GZ_WH_DIS1} -SIM_GZ ESC 3 Minimum Value. +SIM_GZ Wheels 1 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | 0 | 200 | | 100 | -### SIM_GZ_EC_MIN4 (`INT32`) {#SIM_GZ_EC_MIN4} +### SIM_GZ_WH_DIS2 (`INT32`) {#SIM_GZ_WH_DIS2} -SIM_GZ ESC 4 Minimum Value. +SIM_GZ Wheels 2 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | 0 | 200 | | 100 | -### SIM_GZ_EC_MIN5 (`INT32`) {#SIM_GZ_EC_MIN5} +### SIM_GZ_WH_DIS3 (`INT32`) {#SIM_GZ_WH_DIS3} -SIM_GZ ESC 5 Minimum Value. +SIM_GZ Wheels 3 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | 0 | 200 | | 100 | -### SIM_GZ_EC_MIN6 (`INT32`) {#SIM_GZ_EC_MIN6} +### SIM_GZ_WH_DIS4 (`INT32`) {#SIM_GZ_WH_DIS4} -SIM_GZ ESC 6 Minimum Value. +SIM_GZ Wheels 4 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | 0 | 200 | | 100 | -### SIM_GZ_EC_MIN7 (`INT32`) {#SIM_GZ_EC_MIN7} +### SIM_GZ_WH_FAIL1 (`INT32`) {#SIM_GZ_WH_FAIL1} -SIM_GZ ESC 7 Minimum Value. +SIM_GZ Wheels 1 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | -1 | 200 | | -1 | -### SIM_GZ_EC_MIN8 (`INT32`) {#SIM_GZ_EC_MIN8} +### SIM_GZ_WH_FAIL2 (`INT32`) {#SIM_GZ_WH_FAIL2} -SIM_GZ ESC 8 Minimum Value. +SIM_GZ Wheels 2 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | +|   | -1 | 200 | | -1 | -### SIM_GZ_EC_MIN9 (`INT32`) {#SIM_GZ_EC_MIN9} +### SIM_GZ_WH_FAIL3 (`INT32`) {#SIM_GZ_WH_FAIL3} -SIM_GZ ESC 9 Minimum Value. +SIM_GZ Wheels 3 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_EC_REV (`INT32`) {#SIM_GZ_EC_REV} - -Reverse Output Range for SIM_GZ. +|   | -1 | 200 | | -1 | -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +### SIM_GZ_WH_FAIL4 (`INT32`) {#SIM_GZ_WH_FAIL4} -**Bitmask:** +SIM_GZ Wheels 4 Failsafe Value. -- `0`: SIM_GZ ESC 1 -- `1`: SIM_GZ ESC 2 -- `2`: SIM_GZ ESC 3 -- `3`: SIM_GZ ESC 4 -- `4`: SIM_GZ ESC 5 -- `5`: SIM_GZ ESC 6 -- `6`: SIM_GZ ESC 7 -- `7`: SIM_GZ ESC 8 -- `8`: SIM_GZ ESC 9 -- `9`: SIM_GZ ESC 10 -- `10`: SIM_GZ ESC 11 -- `11`: SIM_GZ ESC 12 +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 4095 | | 0 | +|   | -1 | 200 | | -1 | -### SIM_GZ_SV_DIS1 (`INT32`) {#SIM_GZ_SV_DIS1} +### SIM_GZ_WH_FUNC1 (`INT32`) {#SIM_GZ_WH_FUNC1} -SIM_GZ Servo 1 Disarmed Value. +SIM_GZ Wheels 1 Output Function. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS2 (`INT32`) {#SIM_GZ_SV_DIS2} - -SIM_GZ Servo 2 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS3 (`INT32`) {#SIM_GZ_SV_DIS3} - -SIM_GZ Servo 3 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS4 (`INT32`) {#SIM_GZ_SV_DIS4} - -SIM_GZ Servo 4 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS5 (`INT32`) {#SIM_GZ_SV_DIS5} - -SIM_GZ Servo 5 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS6 (`INT32`) {#SIM_GZ_SV_DIS6} - -SIM_GZ Servo 6 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS7 (`INT32`) {#SIM_GZ_SV_DIS7} - -SIM_GZ Servo 7 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_DIS8 (`INT32`) {#SIM_GZ_SV_DIS8} - -SIM_GZ Servo 8 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | - -### SIM_GZ_SV_FAIL1 (`INT32`) {#SIM_GZ_SV_FAIL1} - -SIM_GZ Servo 1 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC1). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL2 (`INT32`) {#SIM_GZ_SV_FAIL2} - -SIM_GZ Servo 2 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC2). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL3 (`INT32`) {#SIM_GZ_SV_FAIL3} - -SIM_GZ Servo 3 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC3). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL4 (`INT32`) {#SIM_GZ_SV_FAIL4} - -SIM_GZ Servo 4 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC4). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL5 (`INT32`) {#SIM_GZ_SV_FAIL5} - -SIM_GZ Servo 5 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC5). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL6 (`INT32`) {#SIM_GZ_SV_FAIL6} - -SIM_GZ Servo 6 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC6). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL7 (`INT32`) {#SIM_GZ_SV_FAIL7} - -SIM_GZ Servo 7 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC7). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FAIL8 (`INT32`) {#SIM_GZ_SV_FAIL8} - -SIM_GZ Servo 8 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_SV_FUNC8). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### SIM_GZ_SV_FUNC1 (`INT32`) {#SIM_GZ_SV_FUNC1} - -SIM_GZ Servo 1 Output Function. - -Select what should be output on SIM_GZ Servo 1. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Wheels 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6542,18 +6489,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC2 (`INT32`) {#SIM_GZ_SV_FUNC2} - -SIM_GZ Servo 2 Output Function. +### SIM_GZ_WH_FUNC2 (`INT32`) {#SIM_GZ_WH_FUNC2} -Select what should be output on SIM_GZ Servo 2. -The default failsafe value is set according to the selected function: +SIM_GZ Wheels 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Wheels 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6613,18 +6553,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC3 (`INT32`) {#SIM_GZ_SV_FUNC3} - -SIM_GZ Servo 3 Output Function. +### SIM_GZ_WH_FUNC3 (`INT32`) {#SIM_GZ_WH_FUNC3} -Select what should be output on SIM_GZ Servo 3. -The default failsafe value is set according to the selected function: +SIM_GZ Wheels 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Wheels 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6684,18 +6617,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC4 (`INT32`) {#SIM_GZ_SV_FUNC4} - -SIM_GZ Servo 4 Output Function. +### SIM_GZ_WH_FUNC4 (`INT32`) {#SIM_GZ_WH_FUNC4} -Select what should be output on SIM_GZ Servo 4. -The default failsafe value is set according to the selected function: +SIM_GZ Wheels 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on SIM_GZ Wheels 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6755,18 +6681,108 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC5 (`INT32`) {#SIM_GZ_SV_FUNC5} +### SIM_GZ_WH_MAX1 (`INT32`) {#SIM_GZ_WH_MAX1} -SIM_GZ Servo 5 Output Function. +SIM_GZ Wheels 1 Maximum Value. -Select what should be output on SIM_GZ Servo 5. -The default failsafe value is set according to the selected function: +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 200 | + +### SIM_GZ_WH_MAX2 (`INT32`) {#SIM_GZ_WH_MAX2} -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +SIM_GZ Wheels 2 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 200 | + +### SIM_GZ_WH_MAX3 (`INT32`) {#SIM_GZ_WH_MAX3} + +SIM_GZ Wheels 3 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 200 | + +### SIM_GZ_WH_MAX4 (`INT32`) {#SIM_GZ_WH_MAX4} + +SIM_GZ Wheels 4 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 200 | + +### SIM_GZ_WH_MIN1 (`INT32`) {#SIM_GZ_WH_MIN1} + +SIM_GZ Wheels 1 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 0 | + +### SIM_GZ_WH_MIN2 (`INT32`) {#SIM_GZ_WH_MIN2} + +SIM_GZ Wheels 2 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 0 | + +### SIM_GZ_WH_MIN3 (`INT32`) {#SIM_GZ_WH_MIN3} + +SIM_GZ Wheels 3 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 0 | + +### SIM_GZ_WH_MIN4 (`INT32`) {#SIM_GZ_WH_MIN4} + +SIM_GZ Wheels 4 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 200 | | 0 | + +### SIM_GZ_WH_REV (`INT32`) {#SIM_GZ_WH_REV} + +Reverse Output Range for SIM_GZ. + +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: SIM_GZ Wheels 1 +- `1`: SIM_GZ Wheels 2 +- `2`: SIM_GZ Wheels 3 +- `3`: SIM_GZ Wheels 4 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 15 | | 0 | + +### TAP_ESC_FUNC1 (`INT32`) {#TAP_ESC_FUNC1} + +TAP ESC Output ESC 1 Output Function. + +Select what should be output on TAP ESC Output ESC 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6826,18 +6842,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC6 (`INT32`) {#SIM_GZ_SV_FUNC6} - -SIM_GZ Servo 6 Output Function. +### TAP_ESC_FUNC2 (`INT32`) {#TAP_ESC_FUNC2} -Select what should be output on SIM_GZ Servo 6. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6897,18 +6906,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC7 (`INT32`) {#SIM_GZ_SV_FUNC7} - -SIM_GZ Servo 7 Output Function. +### TAP_ESC_FUNC3 (`INT32`) {#TAP_ESC_FUNC3} -Select what should be output on SIM_GZ Servo 7. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -6968,18 +6970,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_FUNC8 (`INT32`) {#SIM_GZ_SV_FUNC8} - -SIM_GZ Servo 8 Output Function. +### TAP_ESC_FUNC4 (`INT32`) {#TAP_ESC_FUNC4} -Select what should be output on SIM_GZ Servo 8. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7039,288 +7034,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_SV_MAX1 (`INT32`) {#SIM_GZ_SV_MAX1} - -SIM_GZ Servo 1 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX2 (`INT32`) {#SIM_GZ_SV_MAX2} - -SIM_GZ Servo 2 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX3 (`INT32`) {#SIM_GZ_SV_MAX3} - -SIM_GZ Servo 3 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX4 (`INT32`) {#SIM_GZ_SV_MAX4} - -SIM_GZ Servo 4 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX5 (`INT32`) {#SIM_GZ_SV_MAX5} - -SIM_GZ Servo 5 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX6 (`INT32`) {#SIM_GZ_SV_MAX6} - -SIM_GZ Servo 6 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX7 (`INT32`) {#SIM_GZ_SV_MAX7} - -SIM_GZ Servo 7 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MAX8 (`INT32`) {#SIM_GZ_SV_MAX8} - -SIM_GZ Servo 8 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### SIM_GZ_SV_MIN1 (`INT32`) {#SIM_GZ_SV_MIN1} - -SIM_GZ Servo 1 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN2 (`INT32`) {#SIM_GZ_SV_MIN2} - -SIM_GZ Servo 2 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN3 (`INT32`) {#SIM_GZ_SV_MIN3} - -SIM_GZ Servo 3 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN4 (`INT32`) {#SIM_GZ_SV_MIN4} - -SIM_GZ Servo 4 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN5 (`INT32`) {#SIM_GZ_SV_MIN5} - -SIM_GZ Servo 5 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN6 (`INT32`) {#SIM_GZ_SV_MIN6} - -SIM_GZ Servo 6 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN7 (`INT32`) {#SIM_GZ_SV_MIN7} - -SIM_GZ Servo 7 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_MIN8 (`INT32`) {#SIM_GZ_SV_MIN8} - -SIM_GZ Servo 8 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### SIM_GZ_SV_REV (`INT32`) {#SIM_GZ_SV_REV} - -Reverse Output Range for SIM_GZ. - -Allows to reverse the output range for each channel. -Note: this is only useful for servos. - -**Bitmask:** - -- `0`: SIM_GZ Servo 1 -- `1`: SIM_GZ Servo 2 -- `2`: SIM_GZ Servo 3 -- `3`: SIM_GZ Servo 4 -- `4`: SIM_GZ Servo 5 -- `5`: SIM_GZ Servo 6 -- `6`: SIM_GZ Servo 7 -- `7`: SIM_GZ Servo 8 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 255 | | 0 | - -### SIM_GZ_WH_DIS1 (`INT32`) {#SIM_GZ_WH_DIS1} - -SIM_GZ Wheels 1 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 100 | - -### SIM_GZ_WH_DIS2 (`INT32`) {#SIM_GZ_WH_DIS2} - -SIM_GZ Wheels 2 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 100 | - -### SIM_GZ_WH_DIS3 (`INT32`) {#SIM_GZ_WH_DIS3} - -SIM_GZ Wheels 3 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 100 | - -### SIM_GZ_WH_DIS4 (`INT32`) {#SIM_GZ_WH_DIS4} - -SIM_GZ Wheels 4 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 100 | - -### SIM_GZ_WH_FAIL1 (`INT32`) {#SIM_GZ_WH_FAIL1} - -SIM_GZ Wheels 1 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC1). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 200 | | -1 | - -### SIM_GZ_WH_FAIL2 (`INT32`) {#SIM_GZ_WH_FAIL2} - -SIM_GZ Wheels 2 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC2). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 200 | | -1 | - -### SIM_GZ_WH_FAIL3 (`INT32`) {#SIM_GZ_WH_FAIL3} - -SIM_GZ Wheels 3 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC3). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 200 | | -1 | - -### SIM_GZ_WH_FAIL4 (`INT32`) {#SIM_GZ_WH_FAIL4} - -SIM_GZ Wheels 4 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see SIM_GZ_WH_FUNC4). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 200 | | -1 | - -### SIM_GZ_WH_FUNC1 (`INT32`) {#SIM_GZ_WH_FUNC1} - -SIM_GZ Wheels 1 Output Function. +### TAP_ESC_FUNC5 (`INT32`) {#TAP_ESC_FUNC5} -Select what should be output on SIM_GZ Wheels 1. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7380,18 +7098,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_WH_FUNC2 (`INT32`) {#SIM_GZ_WH_FUNC2} - -SIM_GZ Wheels 2 Output Function. +### TAP_ESC_FUNC6 (`INT32`) {#TAP_ESC_FUNC6} -Select what should be output on SIM_GZ Wheels 2. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7451,18 +7162,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_WH_FUNC3 (`INT32`) {#SIM_GZ_WH_FUNC3} - -SIM_GZ Wheels 3 Output Function. +### TAP_ESC_FUNC7 (`INT32`) {#TAP_ESC_FUNC7} -Select what should be output on SIM_GZ Wheels 3. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7522,18 +7226,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_WH_FUNC4 (`INT32`) {#SIM_GZ_WH_FUNC4} - -SIM_GZ Wheels 4 Output Function. +### TAP_ESC_FUNC8 (`INT32`) {#TAP_ESC_FUNC8} -Select what should be output on SIM_GZ Wheels 4. -The default failsafe value is set according to the selected function: +TAP ESC Output ESC 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on TAP ESC Output ESC 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7593,116 +7290,112 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SIM_GZ_WH_MAX1 (`INT32`) {#SIM_GZ_WH_MAX1} +### TAP_ESC_REV (`INT32`) {#TAP_ESC_REV} -SIM_GZ Wheels 1 Maximum Value. +Reverse Output Range for TAP ESC Output. -Maxmimum output value (when not disarmed). +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: TAP ESC Output ESC 1 +- `1`: TAP ESC Output ESC 2 +- `2`: TAP ESC Output ESC 3 +- `3`: TAP ESC Output ESC 4 +- `4`: TAP ESC Output ESC 5 +- `5`: TAP ESC Output ESC 6 +- `6`: TAP ESC Output ESC 7 +- `7`: TAP ESC Output ESC 8 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 200 | +|   | 0 | 255 | | 0 | -### SIM_GZ_WH_MAX2 (`INT32`) {#SIM_GZ_WH_MAX2} +### UAVCAN_EC_FAIL1 (`INT32`) {#UAVCAN_EC_FAIL1} -SIM_GZ Wheels 2 Maximum Value. +UAVCAN ESC 1 Failsafe Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 200 | +|   | -1 | 8191 | | -1 | -### SIM_GZ_WH_MAX3 (`INT32`) {#SIM_GZ_WH_MAX3} +### UAVCAN_EC_FAIL2 (`INT32`) {#UAVCAN_EC_FAIL2} -SIM_GZ Wheels 3 Maximum Value. +UAVCAN ESC 2 Failsafe Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 200 | +|   | -1 | 8191 | | -1 | -### SIM_GZ_WH_MAX4 (`INT32`) {#SIM_GZ_WH_MAX4} +### UAVCAN_EC_FAIL3 (`INT32`) {#UAVCAN_EC_FAIL3} -SIM_GZ Wheels 4 Maximum Value. +UAVCAN ESC 3 Failsafe Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 200 | +|   | -1 | 8191 | | -1 | -### SIM_GZ_WH_MIN1 (`INT32`) {#SIM_GZ_WH_MIN1} +### UAVCAN_EC_FAIL4 (`INT32`) {#UAVCAN_EC_FAIL4} -SIM_GZ Wheels 1 Minimum Value. +UAVCAN ESC 4 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 0 | +|   | -1 | 8191 | | -1 | -### SIM_GZ_WH_MIN2 (`INT32`) {#SIM_GZ_WH_MIN2} +### UAVCAN_EC_FAIL5 (`INT32`) {#UAVCAN_EC_FAIL5} -SIM_GZ Wheels 2 Minimum Value. +UAVCAN ESC 5 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC5). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 0 | +|   | -1 | 8191 | | -1 | -### SIM_GZ_WH_MIN3 (`INT32`) {#SIM_GZ_WH_MIN3} +### UAVCAN_EC_FAIL6 (`INT32`) {#UAVCAN_EC_FAIL6} -SIM_GZ Wheels 3 Minimum Value. +UAVCAN ESC 6 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 0 | +|   | -1 | 8191 | | -1 | -### SIM_GZ_WH_MIN4 (`INT32`) {#SIM_GZ_WH_MIN4} +### UAVCAN_EC_FAIL7 (`INT32`) {#UAVCAN_EC_FAIL7} -SIM_GZ Wheels 4 Minimum Value. +UAVCAN ESC 7 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC7). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 200 | | 0 | - -### SIM_GZ_WH_REV (`INT32`) {#SIM_GZ_WH_REV} - -Reverse Output Range for SIM_GZ. +|   | -1 | 8191 | | -1 | -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +### UAVCAN_EC_FAIL8 (`INT32`) {#UAVCAN_EC_FAIL8} -**Bitmask:** +UAVCAN ESC 8 Failsafe Value. -- `0`: SIM_GZ Wheels 1 -- `1`: SIM_GZ Wheels 2 -- `2`: SIM_GZ Wheels 3 -- `3`: SIM_GZ Wheels 4 +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC8). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | | 0 | - -### TAP_ESC_FUNC1 (`INT32`) {#TAP_ESC_FUNC1} +|   | -1 | 8191 | | -1 | -TAP ESC Output ESC 1 Output Function. +### UAVCAN_EC_FUNC1 (`INT32`) {#UAVCAN_EC_FUNC1} -Select what should be output on TAP ESC Output ESC 1. -The default failsafe value is set according to the selected function: +UAVCAN ESC 1 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7762,18 +7455,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC2 (`INT32`) {#TAP_ESC_FUNC2} - -TAP ESC Output ESC 2 Output Function. +### UAVCAN_EC_FUNC2 (`INT32`) {#UAVCAN_EC_FUNC2} -Select what should be output on TAP ESC Output ESC 2. -The default failsafe value is set according to the selected function: +UAVCAN ESC 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7833,18 +7519,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC3 (`INT32`) {#TAP_ESC_FUNC3} - -TAP ESC Output ESC 3 Output Function. +### UAVCAN_EC_FUNC3 (`INT32`) {#UAVCAN_EC_FUNC3} -Select what should be output on TAP ESC Output ESC 3. -The default failsafe value is set according to the selected function: +UAVCAN ESC 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7904,18 +7583,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC4 (`INT32`) {#TAP_ESC_FUNC4} - -TAP ESC Output ESC 4 Output Function. +### UAVCAN_EC_FUNC4 (`INT32`) {#UAVCAN_EC_FUNC4} -Select what should be output on TAP ESC Output ESC 4. -The default failsafe value is set according to the selected function: +UAVCAN ESC 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -7975,18 +7647,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC5 (`INT32`) {#TAP_ESC_FUNC5} - -TAP ESC Output ESC 5 Output Function. +### UAVCAN_EC_FUNC5 (`INT32`) {#UAVCAN_EC_FUNC5} -Select what should be output on TAP ESC Output ESC 5. -The default failsafe value is set according to the selected function: +UAVCAN ESC 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8046,18 +7711,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC6 (`INT32`) {#TAP_ESC_FUNC6} - -TAP ESC Output ESC 6 Output Function. +### UAVCAN_EC_FUNC6 (`INT32`) {#UAVCAN_EC_FUNC6} -Select what should be output on TAP ESC Output ESC 6. -The default failsafe value is set according to the selected function: +UAVCAN ESC 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8117,18 +7775,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC7 (`INT32`) {#TAP_ESC_FUNC7} - -TAP ESC Output ESC 7 Output Function. +### UAVCAN_EC_FUNC7 (`INT32`) {#UAVCAN_EC_FUNC7} -Select what should be output on TAP ESC Output ESC 7. -The default failsafe value is set according to the selected function: +UAVCAN ESC 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8188,18 +7839,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_FUNC8 (`INT32`) {#TAP_ESC_FUNC8} - -TAP ESC Output ESC 8 Output Function. +### UAVCAN_EC_FUNC8 (`INT32`) {#UAVCAN_EC_FUNC8} -Select what should be output on TAP ESC Output ESC 8. -The default failsafe value is set according to the selected function: +UAVCAN ESC 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN ESC 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8259,128 +7903,352 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### TAP_ESC_REV (`INT32`) {#TAP_ESC_REV} +### UAVCAN_EC_MAX1 (`INT32`) {#UAVCAN_EC_MAX1} -Reverse Output Range for TAP ESC Output. +UAVCAN ESC 1 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX2 (`INT32`) {#UAVCAN_EC_MAX2} + +UAVCAN ESC 2 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX3 (`INT32`) {#UAVCAN_EC_MAX3} + +UAVCAN ESC 3 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX4 (`INT32`) {#UAVCAN_EC_MAX4} + +UAVCAN ESC 4 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX5 (`INT32`) {#UAVCAN_EC_MAX5} + +UAVCAN ESC 5 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX6 (`INT32`) {#UAVCAN_EC_MAX6} + +UAVCAN ESC 6 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX7 (`INT32`) {#UAVCAN_EC_MAX7} + +UAVCAN ESC 7 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MAX8 (`INT32`) {#UAVCAN_EC_MAX8} + +UAVCAN ESC 8 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UAVCAN_EC_MIN1 (`INT32`) {#UAVCAN_EC_MIN1} + +UAVCAN ESC 1 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN2 (`INT32`) {#UAVCAN_EC_MIN2} + +UAVCAN ESC 2 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN3 (`INT32`) {#UAVCAN_EC_MIN3} + +UAVCAN ESC 3 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN4 (`INT32`) {#UAVCAN_EC_MIN4} + +UAVCAN ESC 4 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN5 (`INT32`) {#UAVCAN_EC_MIN5} + +UAVCAN ESC 5 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN6 (`INT32`) {#UAVCAN_EC_MIN6} + +UAVCAN ESC 6 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN7 (`INT32`) {#UAVCAN_EC_MIN7} + +UAVCAN ESC 7 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_MIN8 (`INT32`) {#UAVCAN_EC_MIN8} + +UAVCAN ESC 8 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UAVCAN_EC_REV (`INT32`) {#UAVCAN_EC_REV} + +Reverse Output Range for UAVCAN. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** -- `0`: TAP ESC Output ESC 1 -- `1`: TAP ESC Output ESC 2 -- `2`: TAP ESC Output ESC 3 -- `3`: TAP ESC Output ESC 4 -- `4`: TAP ESC Output ESC 5 -- `5`: TAP ESC Output ESC 6 -- `6`: TAP ESC Output ESC 7 -- `7`: TAP ESC Output ESC 8 +- `0`: UAVCAN ESC 1 +- `1`: UAVCAN ESC 2 +- `2`: UAVCAN ESC 3 +- `3`: UAVCAN ESC 4 +- `4`: UAVCAN ESC 5 +- `5`: UAVCAN ESC 6 +- `6`: UAVCAN ESC 7 +- `7`: UAVCAN ESC 8 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 255 | | 0 | -### UAVCAN_EC_FAIL1 (`INT32`) {#UAVCAN_EC_FAIL1} +### UAVCAN_SV_DIS1 (`INT32`) {#UAVCAN_SV_DIS1} -UAVCAN ESC 1 Failsafe Value. +UAVCAN Servo 1 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC1). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL2 (`INT32`) {#UAVCAN_EC_FAIL2} +### UAVCAN_SV_DIS2 (`INT32`) {#UAVCAN_SV_DIS2} -UAVCAN ESC 2 Failsafe Value. +UAVCAN Servo 2 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC2). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL3 (`INT32`) {#UAVCAN_EC_FAIL3} +### UAVCAN_SV_DIS3 (`INT32`) {#UAVCAN_SV_DIS3} -UAVCAN ESC 3 Failsafe Value. +UAVCAN Servo 3 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC3). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL4 (`INT32`) {#UAVCAN_EC_FAIL4} +### UAVCAN_SV_DIS4 (`INT32`) {#UAVCAN_SV_DIS4} -UAVCAN ESC 4 Failsafe Value. +UAVCAN Servo 4 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC4). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL5 (`INT32`) {#UAVCAN_EC_FAIL5} +### UAVCAN_SV_DIS5 (`INT32`) {#UAVCAN_SV_DIS5} -UAVCAN ESC 5 Failsafe Value. +UAVCAN Servo 5 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC5). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL6 (`INT32`) {#UAVCAN_EC_FAIL6} +### UAVCAN_SV_DIS6 (`INT32`) {#UAVCAN_SV_DIS6} -UAVCAN ESC 6 Failsafe Value. +UAVCAN Servo 6 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC6). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL7 (`INT32`) {#UAVCAN_EC_FAIL7} +### UAVCAN_SV_DIS7 (`INT32`) {#UAVCAN_SV_DIS7} -UAVCAN ESC 7 Failsafe Value. +UAVCAN Servo 7 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC7). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FAIL8 (`INT32`) {#UAVCAN_EC_FAIL8} +### UAVCAN_SV_DIS8 (`INT32`) {#UAVCAN_SV_DIS8} -UAVCAN ESC 8 Failsafe Value. +UAVCAN Servo 8 Disarmed Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_EC_FUNC8). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | +|   | 0 | 1000 | | 500 | -### UAVCAN_EC_FUNC1 (`INT32`) {#UAVCAN_EC_FUNC1} +### UAVCAN_SV_FAIL1 (`INT32`) {#UAVCAN_SV_FAIL1} -UAVCAN ESC 1 Output Function. +UAVCAN Servo 1 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC1). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL2 (`INT32`) {#UAVCAN_SV_FAIL2} + +UAVCAN Servo 2 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC2). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL3 (`INT32`) {#UAVCAN_SV_FAIL3} + +UAVCAN Servo 3 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC3). -Select what should be output on UAVCAN ESC 1. -The default failsafe value is set according to the selected function: +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL4 (`INT32`) {#UAVCAN_SV_FAIL4} + +UAVCAN Servo 4 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC4). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL5 (`INT32`) {#UAVCAN_SV_FAIL5} + +UAVCAN Servo 5 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC5). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL6 (`INT32`) {#UAVCAN_SV_FAIL6} + +UAVCAN Servo 6 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC6). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL7 (`INT32`) {#UAVCAN_SV_FAIL7} -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +UAVCAN Servo 7 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC7). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FAIL8 (`INT32`) {#UAVCAN_SV_FAIL8} + +UAVCAN Servo 8 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC8). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1000 | | -1 | + +### UAVCAN_SV_FUNC1 (`INT32`) {#UAVCAN_SV_FUNC1} + +UAVCAN Servo 1 Output Function. + +Select what should be output on UAVCAN Servo 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8440,18 +8308,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC2 (`INT32`) {#UAVCAN_EC_FUNC2} - -UAVCAN ESC 2 Output Function. +### UAVCAN_SV_FUNC2 (`INT32`) {#UAVCAN_SV_FUNC2} -Select what should be output on UAVCAN ESC 2. -The default failsafe value is set according to the selected function: +UAVCAN Servo 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8511,18 +8372,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC3 (`INT32`) {#UAVCAN_EC_FUNC3} - -UAVCAN ESC 3 Output Function. +### UAVCAN_SV_FUNC3 (`INT32`) {#UAVCAN_SV_FUNC3} -Select what should be output on UAVCAN ESC 3. -The default failsafe value is set according to the selected function: +UAVCAN Servo 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8582,18 +8436,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC4 (`INT32`) {#UAVCAN_EC_FUNC4} - -UAVCAN ESC 4 Output Function. +### UAVCAN_SV_FUNC4 (`INT32`) {#UAVCAN_SV_FUNC4} -Select what should be output on UAVCAN ESC 4. -The default failsafe value is set according to the selected function: +UAVCAN Servo 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8653,18 +8500,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC5 (`INT32`) {#UAVCAN_EC_FUNC5} - -UAVCAN ESC 5 Output Function. +### UAVCAN_SV_FUNC5 (`INT32`) {#UAVCAN_SV_FUNC5} -Select what should be output on UAVCAN ESC 5. -The default failsafe value is set according to the selected function: +UAVCAN Servo 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8724,18 +8564,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC6 (`INT32`) {#UAVCAN_EC_FUNC6} - -UAVCAN ESC 6 Output Function. +### UAVCAN_SV_FUNC6 (`INT32`) {#UAVCAN_SV_FUNC6} -Select what should be output on UAVCAN ESC 6. -The default failsafe value is set according to the selected function: +UAVCAN Servo 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8795,18 +8628,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC7 (`INT32`) {#UAVCAN_EC_FUNC7} - -UAVCAN ESC 7 Output Function. +### UAVCAN_SV_FUNC7 (`INT32`) {#UAVCAN_SV_FUNC7} -Select what should be output on UAVCAN ESC 7. -The default failsafe value is set according to the selected function: +UAVCAN Servo 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8866,18 +8692,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_FUNC8 (`INT32`) {#UAVCAN_EC_FUNC8} - -UAVCAN ESC 8 Output Function. +### UAVCAN_SV_FUNC8 (`INT32`) {#UAVCAN_SV_FUNC8} -Select what should be output on UAVCAN ESC 8. -The default failsafe value is set according to the selected function: +UAVCAN Servo 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCAN Servo 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -8937,376 +8756,352 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_EC_MAX1 (`INT32`) {#UAVCAN_EC_MAX1} +### UAVCAN_SV_MAX1 (`INT32`) {#UAVCAN_SV_MAX1} -UAVCAN ESC 1 Maximum Value. +UAVCAN Servo 1 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX2 (`INT32`) {#UAVCAN_EC_MAX2} +### UAVCAN_SV_MAX2 (`INT32`) {#UAVCAN_SV_MAX2} -UAVCAN ESC 2 Maximum Value. +UAVCAN Servo 2 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX3 (`INT32`) {#UAVCAN_EC_MAX3} +### UAVCAN_SV_MAX3 (`INT32`) {#UAVCAN_SV_MAX3} -UAVCAN ESC 3 Maximum Value. +UAVCAN Servo 3 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX4 (`INT32`) {#UAVCAN_EC_MAX4} +### UAVCAN_SV_MAX4 (`INT32`) {#UAVCAN_SV_MAX4} -UAVCAN ESC 4 Maximum Value. +UAVCAN Servo 4 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX5 (`INT32`) {#UAVCAN_EC_MAX5} +### UAVCAN_SV_MAX5 (`INT32`) {#UAVCAN_SV_MAX5} -UAVCAN ESC 5 Maximum Value. +UAVCAN Servo 5 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX6 (`INT32`) {#UAVCAN_EC_MAX6} +### UAVCAN_SV_MAX6 (`INT32`) {#UAVCAN_SV_MAX6} -UAVCAN ESC 6 Maximum Value. +UAVCAN Servo 6 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX7 (`INT32`) {#UAVCAN_EC_MAX7} +### UAVCAN_SV_MAX7 (`INT32`) {#UAVCAN_SV_MAX7} -UAVCAN ESC 7 Maximum Value. +UAVCAN Servo 7 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MAX8 (`INT32`) {#UAVCAN_EC_MAX8} +### UAVCAN_SV_MAX8 (`INT32`) {#UAVCAN_SV_MAX8} -UAVCAN ESC 8 Maximum Value. +UAVCAN Servo 8 Maximum Value. Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 1000 | | 1000 | -### UAVCAN_EC_MIN1 (`INT32`) {#UAVCAN_EC_MIN1} +### UAVCAN_SV_MIN1 (`INT32`) {#UAVCAN_SV_MIN1} -UAVCAN ESC 1 Minimum Value. +UAVCAN Servo 1 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN2 (`INT32`) {#UAVCAN_EC_MIN2} +### UAVCAN_SV_MIN2 (`INT32`) {#UAVCAN_SV_MIN2} -UAVCAN ESC 2 Minimum Value. +UAVCAN Servo 2 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN3 (`INT32`) {#UAVCAN_EC_MIN3} +### UAVCAN_SV_MIN3 (`INT32`) {#UAVCAN_SV_MIN3} -UAVCAN ESC 3 Minimum Value. +UAVCAN Servo 3 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN4 (`INT32`) {#UAVCAN_EC_MIN4} +### UAVCAN_SV_MIN4 (`INT32`) {#UAVCAN_SV_MIN4} -UAVCAN ESC 4 Minimum Value. +UAVCAN Servo 4 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN5 (`INT32`) {#UAVCAN_EC_MIN5} +### UAVCAN_SV_MIN5 (`INT32`) {#UAVCAN_SV_MIN5} -UAVCAN ESC 5 Minimum Value. +UAVCAN Servo 5 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN6 (`INT32`) {#UAVCAN_EC_MIN6} +### UAVCAN_SV_MIN6 (`INT32`) {#UAVCAN_SV_MIN6} -UAVCAN ESC 6 Minimum Value. +UAVCAN Servo 6 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN7 (`INT32`) {#UAVCAN_EC_MIN7} +### UAVCAN_SV_MIN7 (`INT32`) {#UAVCAN_SV_MIN7} -UAVCAN ESC 7 Minimum Value. +UAVCAN Servo 7 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_MIN8 (`INT32`) {#UAVCAN_EC_MIN8} +### UAVCAN_SV_MIN8 (`INT32`) {#UAVCAN_SV_MIN8} -UAVCAN ESC 8 Minimum Value. +UAVCAN Servo 8 Minimum Value. Minimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 1000 | | 0 | -### UAVCAN_EC_REV (`INT32`) {#UAVCAN_EC_REV} +### UAVCAN_SV_REV (`INT32`) {#UAVCAN_SV_REV} Reverse Output Range for UAVCAN. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** -- `0`: UAVCAN ESC 1 -- `1`: UAVCAN ESC 2 -- `2`: UAVCAN ESC 3 -- `3`: UAVCAN ESC 4 -- `4`: UAVCAN ESC 5 -- `5`: UAVCAN ESC 6 -- `6`: UAVCAN ESC 7 -- `7`: UAVCAN ESC 8 +- `0`: UAVCAN Servo 1 +- `1`: UAVCAN Servo 2 +- `2`: UAVCAN Servo 3 +- `3`: UAVCAN Servo 4 +- `4`: UAVCAN Servo 5 +- `5`: UAVCAN Servo 6 +- `6`: UAVCAN Servo 7 +- `7`: UAVCAN Servo 8 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 255 | | 0 | -### UAVCAN_SV_DIS1 (`INT32`) {#UAVCAN_SV_DIS1} +### UCAN1_ESC_FAIL1 (`INT32`) {#UCAN1_ESC_FAIL1} -UAVCAN Servo 1 Disarmed Value. +UAVCANv1 ESC 1 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS2 (`INT32`) {#UAVCAN_SV_DIS2} +### UCAN1_ESC_FAIL10 (`INT32`) {#UCAN1_ESC_FAIL10} -UAVCAN Servo 2 Disarmed Value. +UAVCANv1 ESC 10 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC10). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS3 (`INT32`) {#UAVCAN_SV_DIS3} +### UCAN1_ESC_FAIL11 (`INT32`) {#UCAN1_ESC_FAIL11} -UAVCAN Servo 3 Disarmed Value. +UAVCANv1 ESC 11 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC11). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS4 (`INT32`) {#UAVCAN_SV_DIS4} +### UCAN1_ESC_FAIL12 (`INT32`) {#UCAN1_ESC_FAIL12} -UAVCAN Servo 4 Disarmed Value. +UAVCANv1 ESC 12 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC12). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS5 (`INT32`) {#UAVCAN_SV_DIS5} +### UCAN1_ESC_FAIL13 (`INT32`) {#UCAN1_ESC_FAIL13} -UAVCAN Servo 5 Disarmed Value. +UAVCANv1 ESC 13 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC13). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS6 (`INT32`) {#UAVCAN_SV_DIS6} +### UCAN1_ESC_FAIL14 (`INT32`) {#UCAN1_ESC_FAIL14} -UAVCAN Servo 6 Disarmed Value. +UAVCANv1 ESC 14 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC14). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS7 (`INT32`) {#UAVCAN_SV_DIS7} +### UCAN1_ESC_FAIL15 (`INT32`) {#UCAN1_ESC_FAIL15} -UAVCAN Servo 7 Disarmed Value. +UAVCANv1 ESC 15 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC15). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_DIS8 (`INT32`) {#UAVCAN_SV_DIS8} +### UCAN1_ESC_FAIL16 (`INT32`) {#UCAN1_ESC_FAIL16} -UAVCAN Servo 8 Disarmed Value. +UAVCANv1 ESC 16 Failsafe Value. -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC16). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 500 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL1 (`INT32`) {#UAVCAN_SV_FAIL1} +### UCAN1_ESC_FAIL2 (`INT32`) {#UCAN1_ESC_FAIL2} -UAVCAN Servo 1 Failsafe Value. +UAVCANv1 ESC 2 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC1). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL2 (`INT32`) {#UAVCAN_SV_FAIL2} +### UCAN1_ESC_FAIL3 (`INT32`) {#UCAN1_ESC_FAIL3} -UAVCAN Servo 2 Failsafe Value. +UAVCANv1 ESC 3 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC2). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL3 (`INT32`) {#UAVCAN_SV_FAIL3} +### UCAN1_ESC_FAIL4 (`INT32`) {#UCAN1_ESC_FAIL4} -UAVCAN Servo 3 Failsafe Value. +UAVCANv1 ESC 4 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC3). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL4 (`INT32`) {#UAVCAN_SV_FAIL4} +### UCAN1_ESC_FAIL5 (`INT32`) {#UCAN1_ESC_FAIL5} -UAVCAN Servo 4 Failsafe Value. +UAVCANv1 ESC 5 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC4). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC5). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL5 (`INT32`) {#UAVCAN_SV_FAIL5} +### UCAN1_ESC_FAIL6 (`INT32`) {#UCAN1_ESC_FAIL6} -UAVCAN Servo 5 Failsafe Value. +UAVCANv1 ESC 6 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC5). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL6 (`INT32`) {#UAVCAN_SV_FAIL6} +### UCAN1_ESC_FAIL7 (`INT32`) {#UCAN1_ESC_FAIL7} -UAVCAN Servo 6 Failsafe Value. +UAVCANv1 ESC 7 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC6). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC7). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL7 (`INT32`) {#UAVCAN_SV_FAIL7} +### UCAN1_ESC_FAIL8 (`INT32`) {#UCAN1_ESC_FAIL8} -UAVCAN Servo 7 Failsafe Value. +UAVCANv1 ESC 8 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC7). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC8). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | +|   | -1 | 8191 | | -1 | -### UAVCAN_SV_FAIL8 (`INT32`) {#UAVCAN_SV_FAIL8} +### UCAN1_ESC_FAIL9 (`INT32`) {#UCAN1_ESC_FAIL9} -UAVCAN Servo 8 Failsafe Value. +UAVCANv1 ESC 9 Failsafe Value. -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UAVCAN_SV_FUNC8). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC9). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1000 | | -1 | - -### UAVCAN_SV_FUNC1 (`INT32`) {#UAVCAN_SV_FUNC1} +|   | -1 | 8191 | | -1 | -UAVCAN Servo 1 Output Function. +### UCAN1_ESC_FUNC1 (`INT32`) {#UCAN1_ESC_FUNC1} -Select what should be output on UAVCAN Servo 1. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 1 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9366,18 +9161,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC2 (`INT32`) {#UAVCAN_SV_FUNC2} - -UAVCAN Servo 2 Output Function. +### UCAN1_ESC_FUNC10 (`INT32`) {#UCAN1_ESC_FUNC10} -Select what should be output on UAVCAN Servo 2. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 10 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9437,18 +9225,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC3 (`INT32`) {#UAVCAN_SV_FUNC3} - -UAVCAN Servo 3 Output Function. +### UCAN1_ESC_FUNC11 (`INT32`) {#UCAN1_ESC_FUNC11} -Select what should be output on UAVCAN Servo 3. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 11 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9508,18 +9289,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC4 (`INT32`) {#UAVCAN_SV_FUNC4} - -UAVCAN Servo 4 Output Function. +### UCAN1_ESC_FUNC12 (`INT32`) {#UCAN1_ESC_FUNC12} -Select what should be output on UAVCAN Servo 4. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 12 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9579,18 +9353,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC5 (`INT32`) {#UAVCAN_SV_FUNC5} - -UAVCAN Servo 5 Output Function. +### UCAN1_ESC_FUNC13 (`INT32`) {#UCAN1_ESC_FUNC13} -Select what should be output on UAVCAN Servo 5. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 13 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9650,18 +9417,75 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC6 (`INT32`) {#UAVCAN_SV_FUNC6} +### UCAN1_ESC_FUNC14 (`INT32`) {#UCAN1_ESC_FUNC14} -UAVCAN Servo 6 Output Function. +UAVCANv1 ESC 14 Output Function. + +Select what should be output on UAVCANv1 ESC 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + +### UCAN1_ESC_FUNC15 (`INT32`) {#UCAN1_ESC_FUNC15} -Select what should be output on UAVCAN Servo 6. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 15 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9721,18 +9545,75 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC7 (`INT32`) {#UAVCAN_SV_FUNC7} +### UCAN1_ESC_FUNC16 (`INT32`) {#UCAN1_ESC_FUNC16} -UAVCAN Servo 7 Output Function. +UAVCANv1 ESC 16 Output Function. + +Select what should be output on UAVCANv1 ESC 16. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + +### UCAN1_ESC_FUNC2 (`INT32`) {#UCAN1_ESC_FUNC2} -Select what should be output on UAVCAN Servo 7. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9792,18 +9673,75 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_FUNC8 (`INT32`) {#UAVCAN_SV_FUNC8} +### UCAN1_ESC_FUNC3 (`INT32`) {#UCAN1_ESC_FUNC3} -UAVCAN Servo 8 Output Function. +UAVCANv1 ESC 3 Output Function. + +Select what should be output on UAVCANv1 ESC 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + +### UCAN1_ESC_FUNC4 (`INT32`) {#UCAN1_ESC_FUNC4} -Select what should be output on UAVCAN Servo 8. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -9863,376 +9801,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UAVCAN_SV_MAX1 (`INT32`) {#UAVCAN_SV_MAX1} - -UAVCAN Servo 1 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX2 (`INT32`) {#UAVCAN_SV_MAX2} - -UAVCAN Servo 2 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX3 (`INT32`) {#UAVCAN_SV_MAX3} - -UAVCAN Servo 3 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX4 (`INT32`) {#UAVCAN_SV_MAX4} - -UAVCAN Servo 4 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX5 (`INT32`) {#UAVCAN_SV_MAX5} - -UAVCAN Servo 5 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX6 (`INT32`) {#UAVCAN_SV_MAX6} - -UAVCAN Servo 6 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX7 (`INT32`) {#UAVCAN_SV_MAX7} - -UAVCAN Servo 7 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MAX8 (`INT32`) {#UAVCAN_SV_MAX8} - -UAVCAN Servo 8 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 1000 | - -### UAVCAN_SV_MIN1 (`INT32`) {#UAVCAN_SV_MIN1} - -UAVCAN Servo 1 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN2 (`INT32`) {#UAVCAN_SV_MIN2} - -UAVCAN Servo 2 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN3 (`INT32`) {#UAVCAN_SV_MIN3} - -UAVCAN Servo 3 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN4 (`INT32`) {#UAVCAN_SV_MIN4} - -UAVCAN Servo 4 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN5 (`INT32`) {#UAVCAN_SV_MIN5} - -UAVCAN Servo 5 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN6 (`INT32`) {#UAVCAN_SV_MIN6} - -UAVCAN Servo 6 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN7 (`INT32`) {#UAVCAN_SV_MIN7} - -UAVCAN Servo 7 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_MIN8 (`INT32`) {#UAVCAN_SV_MIN8} - -UAVCAN Servo 8 Minimum Value. - -Minimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1000 | | 0 | - -### UAVCAN_SV_REV (`INT32`) {#UAVCAN_SV_REV} - -Reverse Output Range for UAVCAN. - -Allows to reverse the output range for each channel. -Note: this is only useful for servos. - -**Bitmask:** - -- `0`: UAVCAN Servo 1 -- `1`: UAVCAN Servo 2 -- `2`: UAVCAN Servo 3 -- `3`: UAVCAN Servo 4 -- `4`: UAVCAN Servo 5 -- `5`: UAVCAN Servo 6 -- `6`: UAVCAN Servo 7 -- `7`: UAVCAN Servo 8 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 255 | | 0 | - -### UCAN1_ESC_FAIL1 (`INT32`) {#UCAN1_ESC_FAIL1} - -UAVCANv1 ESC 1 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC1). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL10 (`INT32`) {#UCAN1_ESC_FAIL10} - -UAVCANv1 ESC 10 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC10). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL11 (`INT32`) {#UCAN1_ESC_FAIL11} - -UAVCANv1 ESC 11 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC11). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL12 (`INT32`) {#UCAN1_ESC_FAIL12} - -UAVCANv1 ESC 12 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC12). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL13 (`INT32`) {#UCAN1_ESC_FAIL13} - -UAVCANv1 ESC 13 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC13). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL14 (`INT32`) {#UCAN1_ESC_FAIL14} - -UAVCANv1 ESC 14 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC14). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL15 (`INT32`) {#UCAN1_ESC_FAIL15} - -UAVCANv1 ESC 15 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC15). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL16 (`INT32`) {#UCAN1_ESC_FAIL16} - -UAVCANv1 ESC 16 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC16). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL2 (`INT32`) {#UCAN1_ESC_FAIL2} - -UAVCANv1 ESC 2 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC2). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL3 (`INT32`) {#UCAN1_ESC_FAIL3} - -UAVCANv1 ESC 3 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC3). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL4 (`INT32`) {#UCAN1_ESC_FAIL4} - -UAVCANv1 ESC 4 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC4). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL5 (`INT32`) {#UCAN1_ESC_FAIL5} - -UAVCANv1 ESC 5 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC5). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL6 (`INT32`) {#UCAN1_ESC_FAIL6} - -UAVCANv1 ESC 6 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC6). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL7 (`INT32`) {#UCAN1_ESC_FAIL7} - -UAVCANv1 ESC 7 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC7). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL8 (`INT32`) {#UCAN1_ESC_FAIL8} - -UAVCANv1 ESC 8 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC8). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FAIL9 (`INT32`) {#UCAN1_ESC_FAIL9} - -UAVCANv1 ESC 9 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see UCAN1_ESC_FUNC9). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 8191 | | -1 | - -### UCAN1_ESC_FUNC1 (`INT32`) {#UCAN1_ESC_FUNC1} - -UAVCANv1 ESC 1 Output Function. +### UCAN1_ESC_FUNC5 (`INT32`) {#UCAN1_ESC_FUNC5} -Select what should be output on UAVCANv1 ESC 1. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10292,18 +9865,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC10 (`INT32`) {#UCAN1_ESC_FUNC10} - -UAVCANv1 ESC 10 Output Function. +### UCAN1_ESC_FUNC6 (`INT32`) {#UCAN1_ESC_FUNC6} -Select what should be output on UAVCANv1 ESC 10. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10363,18 +9929,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC11 (`INT32`) {#UCAN1_ESC_FUNC11} - -UAVCANv1 ESC 11 Output Function. +### UCAN1_ESC_FUNC7 (`INT32`) {#UCAN1_ESC_FUNC7} -Select what should be output on UAVCANv1 ESC 11. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10434,18 +9993,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC12 (`INT32`) {#UCAN1_ESC_FUNC12} - -UAVCANv1 ESC 12 Output Function. +### UCAN1_ESC_FUNC8 (`INT32`) {#UCAN1_ESC_FUNC8} -Select what should be output on UAVCANv1 ESC 12. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10505,18 +10057,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC13 (`INT32`) {#UCAN1_ESC_FUNC13} - -UAVCANv1 ESC 13 Output Function. +### UCAN1_ESC_FUNC9 (`INT32`) {#UCAN1_ESC_FUNC9} -Select what should be output on UAVCANv1 ESC 13. -The default failsafe value is set according to the selected function: +UAVCANv1 ESC 9 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on UAVCANv1 ESC 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10576,184 +10121,384 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC14 (`INT32`) {#UCAN1_ESC_FUNC14} +### UCAN1_ESC_MAX1 (`INT32`) {#UCAN1_ESC_MAX1} -UAVCANv1 ESC 14 Output Function. +UAVCANv1 ESC 1 Maximum Value. -Select what should be output on UAVCANv1 ESC 14. -The default failsafe value is set according to the selected function: +Maxmimum output value (when not disarmed). -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | -**Values:** +### UCAN1_ESC_MAX10 (`INT32`) {#UCAN1_ESC_MAX10} -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter +UAVCANv1 ESC 10 Maximum Value. + +Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0 | 8191 | | 8191 | -### UCAN1_ESC_FUNC15 (`INT32`) {#UCAN1_ESC_FUNC15} +### UCAN1_ESC_MAX11 (`INT32`) {#UCAN1_ESC_MAX11} -UAVCANv1 ESC 15 Output Function. +UAVCANv1 ESC 11 Maximum Value. -Select what should be output on UAVCANv1 ESC 15. -The default failsafe value is set according to the selected function: +Maxmimum output value (when not disarmed). -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | -**Values:** +### UCAN1_ESC_MAX12 (`INT32`) {#UCAN1_ESC_MAX12} -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter +UAVCANv1 ESC 12 Maximum Value. + +Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0 | 8191 | | 8191 | -### UCAN1_ESC_FUNC16 (`INT32`) {#UCAN1_ESC_FUNC16} +### UCAN1_ESC_MAX13 (`INT32`) {#UCAN1_ESC_MAX13} -UAVCANv1 ESC 16 Output Function. +UAVCANv1 ESC 13 Maximum Value. -Select what should be output on UAVCANv1 ESC 16. -The default failsafe value is set according to the selected function: +Maxmimum output value (when not disarmed). -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | -**Values:** +### UCAN1_ESC_MAX14 (`INT32`) {#UCAN1_ESC_MAX14} -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 +UAVCANv1 ESC 14 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX15 (`INT32`) {#UCAN1_ESC_MAX15} + +UAVCANv1 ESC 15 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX16 (`INT32`) {#UCAN1_ESC_MAX16} + +UAVCANv1 ESC 16 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX2 (`INT32`) {#UCAN1_ESC_MAX2} + +UAVCANv1 ESC 2 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX3 (`INT32`) {#UCAN1_ESC_MAX3} + +UAVCANv1 ESC 3 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX4 (`INT32`) {#UCAN1_ESC_MAX4} + +UAVCANv1 ESC 4 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX5 (`INT32`) {#UCAN1_ESC_MAX5} + +UAVCANv1 ESC 5 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX6 (`INT32`) {#UCAN1_ESC_MAX6} + +UAVCANv1 ESC 6 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX7 (`INT32`) {#UCAN1_ESC_MAX7} + +UAVCANv1 ESC 7 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX8 (`INT32`) {#UCAN1_ESC_MAX8} + +UAVCANv1 ESC 8 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MAX9 (`INT32`) {#UCAN1_ESC_MAX9} + +UAVCANv1 ESC 9 Maximum Value. + +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 8191 | + +### UCAN1_ESC_MIN1 (`INT32`) {#UCAN1_ESC_MIN1} + +UAVCANv1 ESC 1 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN10 (`INT32`) {#UCAN1_ESC_MIN10} + +UAVCANv1 ESC 10 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN11 (`INT32`) {#UCAN1_ESC_MIN11} + +UAVCANv1 ESC 11 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN12 (`INT32`) {#UCAN1_ESC_MIN12} + +UAVCANv1 ESC 12 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN13 (`INT32`) {#UCAN1_ESC_MIN13} + +UAVCANv1 ESC 13 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN14 (`INT32`) {#UCAN1_ESC_MIN14} + +UAVCANv1 ESC 14 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN15 (`INT32`) {#UCAN1_ESC_MIN15} + +UAVCANv1 ESC 15 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN16 (`INT32`) {#UCAN1_ESC_MIN16} + +UAVCANv1 ESC 16 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN2 (`INT32`) {#UCAN1_ESC_MIN2} + +UAVCANv1 ESC 2 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN3 (`INT32`) {#UCAN1_ESC_MIN3} + +UAVCANv1 ESC 3 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN4 (`INT32`) {#UCAN1_ESC_MIN4} + +UAVCANv1 ESC 4 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN5 (`INT32`) {#UCAN1_ESC_MIN5} + +UAVCANv1 ESC 5 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN6 (`INT32`) {#UCAN1_ESC_MIN6} + +UAVCANv1 ESC 6 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN7 (`INT32`) {#UCAN1_ESC_MIN7} + +UAVCANv1 ESC 7 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN8 (`INT32`) {#UCAN1_ESC_MIN8} + +UAVCANv1 ESC 8 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_MIN9 (`INT32`) {#UCAN1_ESC_MIN9} + +UAVCANv1 ESC 9 Minimum Value. + +Minimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 8191 | | 1 | + +### UCAN1_ESC_REV (`INT32`) {#UCAN1_ESC_REV} + +Reverse Output Range for UAVCANv1. + +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: UAVCANv1 ESC 1 +- `1`: UAVCANv1 ESC 2 +- `2`: UAVCANv1 ESC 3 +- `3`: UAVCANv1 ESC 4 +- `4`: UAVCANv1 ESC 5 +- `5`: UAVCANv1 ESC 6 +- `6`: UAVCANv1 ESC 7 +- `7`: UAVCANv1 ESC 8 +- `8`: UAVCANv1 ESC 9 +- `9`: UAVCANv1 ESC 10 +- `10`: UAVCANv1 ESC 11 +- `11`: UAVCANv1 ESC 12 +- `12`: UAVCANv1 ESC 13 +- `13`: UAVCANv1 ESC 14 +- `14`: UAVCANv1 ESC 15 +- `15`: UAVCANv1 ESC 16 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 65535 | | 0 | + +### VOXL2_IO_FUNC1 (`INT32`) {#VOXL2_IO_FUNC1} + +VOXL2 IO Output PWM Channel 1 Output Function. + +Select what should be output on VOXL2 IO Output PWM Channel 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 - `207`: Servo 7 - `208`: Servo 8 - `301`: Peripheral via Actuator Set 1 @@ -10789,18 +10534,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC2 (`INT32`) {#UCAN1_ESC_FUNC2} - -UAVCANv1 ESC 2 Output Function. +### VOXL2_IO_FUNC2 (`INT32`) {#VOXL2_IO_FUNC2} -Select what should be output on UAVCANv1 ESC 2. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10860,18 +10598,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC3 (`INT32`) {#UCAN1_ESC_FUNC3} - -UAVCANv1 ESC 3 Output Function. +### VOXL2_IO_FUNC3 (`INT32`) {#VOXL2_IO_FUNC3} -Select what should be output on UAVCANv1 ESC 3. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -10931,18 +10662,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC4 (`INT32`) {#UCAN1_ESC_FUNC4} - -UAVCANv1 ESC 4 Output Function. +### VOXL2_IO_FUNC4 (`INT32`) {#VOXL2_IO_FUNC4} -Select what should be output on UAVCANv1 ESC 4. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11002,18 +10726,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC5 (`INT32`) {#UCAN1_ESC_FUNC5} - -UAVCANv1 ESC 5 Output Function. +### VOXL2_IO_FUNC5 (`INT32`) {#VOXL2_IO_FUNC5} -Select what should be output on UAVCANv1 ESC 5. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11073,18 +10790,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC6 (`INT32`) {#UCAN1_ESC_FUNC6} - -UAVCANv1 ESC 6 Output Function. +### VOXL2_IO_FUNC6 (`INT32`) {#VOXL2_IO_FUNC6} -Select what should be output on UAVCANv1 ESC 6. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11144,18 +10854,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC7 (`INT32`) {#UCAN1_ESC_FUNC7} - -UAVCANv1 ESC 7 Output Function. +### VOXL2_IO_FUNC7 (`INT32`) {#VOXL2_IO_FUNC7} -Select what should be output on UAVCANv1 ESC 7. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11215,18 +10918,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC8 (`INT32`) {#UCAN1_ESC_FUNC8} - -UAVCANv1 ESC 8 Output Function. +### VOXL2_IO_FUNC8 (`INT32`) {#VOXL2_IO_FUNC8} -Select what should be output on UAVCANv1 ESC 8. -The default failsafe value is set according to the selected function: +VOXL2 IO Output PWM Channel 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL2 IO Output PWM Channel 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11286,18 +10982,32 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_FUNC9 (`INT32`) {#UCAN1_ESC_FUNC9} +### VOXL2_IO_REV (`INT32`) {#VOXL2_IO_REV} -UAVCANv1 ESC 9 Output Function. +Reverse Output Range for VOXL2 IO Output. + +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: VOXL2 IO Output PWM Channel 1 +- `1`: VOXL2 IO Output PWM Channel 2 +- `2`: VOXL2 IO Output PWM Channel 3 +- `3`: VOXL2 IO Output PWM Channel 4 +- `4`: VOXL2 IO Output PWM Channel 5 +- `5`: VOXL2 IO Output PWM Channel 6 +- `6`: VOXL2 IO Output PWM Channel 7 +- `7`: VOXL2 IO Output PWM Channel 8 + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 255 | | 0 | + +### VOXL_ESC_FUNC1 (`INT32`) {#VOXL_ESC_FUNC1} -Select what should be output on UAVCANv1 ESC 9. -The default failsafe value is set according to the selected function: +VOXL ESC Output ESC 1 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on VOXL ESC Output ESC 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11357,368 +11067,540 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### UCAN1_ESC_MAX1 (`INT32`) {#UCAN1_ESC_MAX1} - -UAVCANv1 ESC 1 Maximum Value. - -Maxmimum output value (when not disarmed). +### VOXL_ESC_FUNC2 (`INT32`) {#VOXL_ESC_FUNC2} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +VOXL ESC Output ESC 2 Output Function. -### UCAN1_ESC_MAX10 (`INT32`) {#UCAN1_ESC_MAX10} +Select what should be output on VOXL ESC Output ESC 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest -UAVCANv1 ESC 10 Maximum Value. +**Values:** -Maxmimum output value (when not disarmed). +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | | | | 0 | -### UCAN1_ESC_MAX11 (`INT32`) {#UCAN1_ESC_MAX11} +### VOXL_ESC_FUNC3 (`INT32`) {#VOXL_ESC_FUNC3} -UAVCANv1 ESC 11 Maximum Value. +VOXL ESC Output ESC 3 Output Function. -Maxmimum output value (when not disarmed). +Select what should be output on VOXL ESC Output ESC 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | | | | 0 | -### UCAN1_ESC_MAX12 (`INT32`) {#UCAN1_ESC_MAX12} +### VOXL_ESC_FUNC4 (`INT32`) {#VOXL_ESC_FUNC4} -UAVCANv1 ESC 12 Maximum Value. +VOXL ESC Output ESC 4 Output Function. -Maxmimum output value (when not disarmed). +Select what should be output on VOXL ESC Output ESC 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest + +**Values:** + +- `0`: Disabled +- `1`: Constant Min +- `2`: Constant Max +- `101`: Motor 1 +- `102`: Motor 2 +- `103`: Motor 3 +- `104`: Motor 4 +- `105`: Motor 5 +- `106`: Motor 6 +- `107`: Motor 7 +- `108`: Motor 8 +- `109`: Motor 9 +- `110`: Motor 10 +- `111`: Motor 11 +- `112`: Motor 12 +- `201`: Servo 1 +- `202`: Servo 2 +- `203`: Servo 3 +- `204`: Servo 4 +- `205`: Servo 5 +- `206`: Servo 6 +- `207`: Servo 7 +- `208`: Servo 8 +- `301`: Peripheral via Actuator Set 1 +- `302`: Peripheral via Actuator Set 2 +- `303`: Peripheral via Actuator Set 3 +- `304`: Peripheral via Actuator Set 4 +- `305`: Peripheral via Actuator Set 5 +- `306`: Peripheral via Actuator Set 6 +- `400`: Landing Gear +- `401`: Parachute +- `402`: RC Roll +- `403`: RC Pitch +- `404`: RC Throttle +- `405`: RC Yaw +- `406`: RC Flaps +- `407`: RC AUX 1 +- `408`: RC AUX 2 +- `409`: RC AUX 3 +- `410`: RC AUX 4 +- `411`: RC AUX 5 +- `412`: RC AUX 6 +- `420`: Gimbal Roll +- `421`: Gimbal Pitch +- `422`: Gimbal Yaw +- `430`: Gripper +- `440`: Landing Gear Wheel +- `450`: IC Engine Ignition +- `451`: IC Engine Throttle +- `452`: IC Engine Choke +- `453`: IC Engine Starter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | | | | 0 | -### UCAN1_ESC_MAX13 (`INT32`) {#UCAN1_ESC_MAX13} +### VOXL_ESC_REV (`INT32`) {#VOXL_ESC_REV} -UAVCANv1 ESC 13 Maximum Value. +Reverse Output Range for VOXL ESC Output. -Maxmimum output value (when not disarmed). +Allows to reverse the output range for each channel. Note: this is only useful for servos. + +**Bitmask:** + +- `0`: VOXL ESC Output ESC 1 +- `1`: VOXL ESC Output ESC 2 +- `2`: VOXL ESC Output ESC 3 +- `3`: VOXL ESC Output ESC 4 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 15 | | 0 | -### UCAN1_ESC_MAX14 (`INT32`) {#UCAN1_ESC_MAX14} +### VTQ_IO_DIS0 (`INT32`) {#VTQ_IO_DIS0} -UAVCANv1 ESC 14 Maximum Value. +Vertiq IO CVI 0 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX15 (`INT32`) {#UCAN1_ESC_MAX15} +### VTQ_IO_DIS1 (`INT32`) {#VTQ_IO_DIS1} -UAVCANv1 ESC 15 Maximum Value. +Vertiq IO CVI 1 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX16 (`INT32`) {#UCAN1_ESC_MAX16} +### VTQ_IO_DIS10 (`INT32`) {#VTQ_IO_DIS10} -UAVCANv1 ESC 16 Maximum Value. +Vertiq IO CVI 10 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX2 (`INT32`) {#UCAN1_ESC_MAX2} +### VTQ_IO_DIS11 (`INT32`) {#VTQ_IO_DIS11} -UAVCANv1 ESC 2 Maximum Value. +Vertiq IO CVI 11 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX3 (`INT32`) {#UCAN1_ESC_MAX3} +### VTQ_IO_DIS12 (`INT32`) {#VTQ_IO_DIS12} -UAVCANv1 ESC 3 Maximum Value. +Vertiq IO CVI 12 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX4 (`INT32`) {#UCAN1_ESC_MAX4} +### VTQ_IO_DIS13 (`INT32`) {#VTQ_IO_DIS13} -UAVCANv1 ESC 4 Maximum Value. +Vertiq IO CVI 13 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX5 (`INT32`) {#UCAN1_ESC_MAX5} +### VTQ_IO_DIS14 (`INT32`) {#VTQ_IO_DIS14} -UAVCANv1 ESC 5 Maximum Value. +Vertiq IO CVI 14 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX6 (`INT32`) {#UCAN1_ESC_MAX6} +### VTQ_IO_DIS15 (`INT32`) {#VTQ_IO_DIS15} -UAVCANv1 ESC 6 Maximum Value. +Vertiq IO CVI 15 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX7 (`INT32`) {#UCAN1_ESC_MAX7} +### VTQ_IO_DIS2 (`INT32`) {#VTQ_IO_DIS2} -UAVCANv1 ESC 7 Maximum Value. +Vertiq IO CVI 2 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX8 (`INT32`) {#UCAN1_ESC_MAX8} +### VTQ_IO_DIS3 (`INT32`) {#VTQ_IO_DIS3} -UAVCANv1 ESC 8 Maximum Value. +Vertiq IO CVI 3 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MAX9 (`INT32`) {#UCAN1_ESC_MAX9} +### VTQ_IO_DIS4 (`INT32`) {#VTQ_IO_DIS4} -UAVCANv1 ESC 9 Maximum Value. +Vertiq IO CVI 4 Disarmed Value. -Maxmimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 8191 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MIN1 (`INT32`) {#UCAN1_ESC_MIN1} +### VTQ_IO_DIS5 (`INT32`) {#VTQ_IO_DIS5} -UAVCANv1 ESC 1 Minimum Value. +Vertiq IO CVI 5 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MIN10 (`INT32`) {#UCAN1_ESC_MIN10} +### VTQ_IO_DIS6 (`INT32`) {#VTQ_IO_DIS6} -UAVCANv1 ESC 10 Minimum Value. +Vertiq IO CVI 6 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MIN11 (`INT32`) {#UCAN1_ESC_MIN11} +### VTQ_IO_DIS7 (`INT32`) {#VTQ_IO_DIS7} -UAVCANv1 ESC 11 Minimum Value. +Vertiq IO CVI 7 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MIN12 (`INT32`) {#UCAN1_ESC_MIN12} +### VTQ_IO_DIS8 (`INT32`) {#VTQ_IO_DIS8} -UAVCANv1 ESC 12 Minimum Value. +Vertiq IO CVI 8 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MIN13 (`INT32`) {#UCAN1_ESC_MIN13} +### VTQ_IO_DIS9 (`INT32`) {#VTQ_IO_DIS9} -UAVCANv1 ESC 13 Minimum Value. +Vertiq IO CVI 9 Disarmed Value. -Minimum output value (when not disarmed). +This is the output value that is set when not armed. Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | 0 | 65535 | | 0 | -### UCAN1_ESC_MIN14 (`INT32`) {#UCAN1_ESC_MIN14} +### VTQ_IO_FAIL0 (`INT32`) {#VTQ_IO_FAIL0} -UAVCANv1 ESC 14 Minimum Value. +Vertiq IO CVI 0 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC0). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN15 (`INT32`) {#UCAN1_ESC_MIN15} +### VTQ_IO_FAIL1 (`INT32`) {#VTQ_IO_FAIL1} -UAVCANv1 ESC 15 Minimum Value. +Vertiq IO CVI 1 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC1). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN16 (`INT32`) {#UCAN1_ESC_MIN16} +### VTQ_IO_FAIL10 (`INT32`) {#VTQ_IO_FAIL10} -UAVCANv1 ESC 16 Minimum Value. +Vertiq IO CVI 10 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC10). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN2 (`INT32`) {#UCAN1_ESC_MIN2} +### VTQ_IO_FAIL11 (`INT32`) {#VTQ_IO_FAIL11} -UAVCANv1 ESC 2 Minimum Value. +Vertiq IO CVI 11 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC11). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN3 (`INT32`) {#UCAN1_ESC_MIN3} +### VTQ_IO_FAIL12 (`INT32`) {#VTQ_IO_FAIL12} -UAVCANv1 ESC 3 Minimum Value. +Vertiq IO CVI 12 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC12). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN4 (`INT32`) {#UCAN1_ESC_MIN4} +### VTQ_IO_FAIL13 (`INT32`) {#VTQ_IO_FAIL13} -UAVCANv1 ESC 4 Minimum Value. +Vertiq IO CVI 13 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC13). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN5 (`INT32`) {#UCAN1_ESC_MIN5} +### VTQ_IO_FAIL14 (`INT32`) {#VTQ_IO_FAIL14} -UAVCANv1 ESC 5 Minimum Value. +Vertiq IO CVI 14 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC14). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN6 (`INT32`) {#UCAN1_ESC_MIN6} +### VTQ_IO_FAIL15 (`INT32`) {#VTQ_IO_FAIL15} -UAVCANv1 ESC 6 Minimum Value. +Vertiq IO CVI 15 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC15). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN7 (`INT32`) {#UCAN1_ESC_MIN7} +### VTQ_IO_FAIL2 (`INT32`) {#VTQ_IO_FAIL2} -UAVCANv1 ESC 7 Minimum Value. +Vertiq IO CVI 2 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC2). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN8 (`INT32`) {#UCAN1_ESC_MIN8} +### VTQ_IO_FAIL3 (`INT32`) {#VTQ_IO_FAIL3} -UAVCANv1 ESC 8 Minimum Value. +Vertiq IO CVI 3 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC3). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_MIN9 (`INT32`) {#UCAN1_ESC_MIN9} +### VTQ_IO_FAIL4 (`INT32`) {#VTQ_IO_FAIL4} -UAVCANv1 ESC 9 Minimum Value. +Vertiq IO CVI 4 Failsafe Value. -Minimum output value (when not disarmed). +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC4). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8191 | | 1 | +|   | -1 | 500 | | -1 | -### UCAN1_ESC_REV (`INT32`) {#UCAN1_ESC_REV} +### VTQ_IO_FAIL5 (`INT32`) {#VTQ_IO_FAIL5} -Reverse Output Range for UAVCANv1. +Vertiq IO CVI 5 Failsafe Value. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC5). -**Bitmask:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 500 | | -1 | -- `0`: UAVCANv1 ESC 1 -- `1`: UAVCANv1 ESC 2 -- `2`: UAVCANv1 ESC 3 -- `3`: UAVCANv1 ESC 4 -- `4`: UAVCANv1 ESC 5 -- `5`: UAVCANv1 ESC 6 -- `6`: UAVCANv1 ESC 7 -- `7`: UAVCANv1 ESC 8 -- `8`: UAVCANv1 ESC 9 -- `9`: UAVCANv1 ESC 10 -- `10`: UAVCANv1 ESC 11 -- `11`: UAVCANv1 ESC 12 -- `12`: UAVCANv1 ESC 13 -- `13`: UAVCANv1 ESC 14 -- `14`: UAVCANv1 ESC 15 -- `15`: UAVCANv1 ESC 16 +### VTQ_IO_FAIL6 (`INT32`) {#VTQ_IO_FAIL6} + +Vertiq IO CVI 6 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC6). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | +|   | -1 | 500 | | -1 | -### VOXL2_IO_FUNC1 (`INT32`) {#VOXL2_IO_FUNC1} +### VTQ_IO_FAIL7 (`INT32`) {#VTQ_IO_FAIL7} -VOXL2 IO Output PWM Channel 1 Output Function. +Vertiq IO CVI 7 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC7). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 500 | | -1 | + +### VTQ_IO_FAIL8 (`INT32`) {#VTQ_IO_FAIL8} + +Vertiq IO CVI 8 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC8). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 500 | | -1 | + +### VTQ_IO_FAIL9 (`INT32`) {#VTQ_IO_FAIL9} + +Vertiq IO CVI 9 Failsafe Value. + +This is the output value that is set when in failsafe mode. When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC9). -Select what should be output on VOXL2 IO Output PWM Channel 1. -The default failsafe value is set according to the selected function: +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 500 | | -1 | -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +### VTQ_IO_FUNC0 (`INT32`) {#VTQ_IO_FUNC0} + +Vertiq IO CVI 0 Output Function. + +Select what should be output on Vertiq IO CVI 0. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11778,18 +11660,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC2 (`INT32`) {#VOXL2_IO_FUNC2} - -VOXL2 IO Output PWM Channel 2 Output Function. +### VTQ_IO_FUNC1 (`INT32`) {#VTQ_IO_FUNC1} -Select what should be output on VOXL2 IO Output PWM Channel 2. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 1 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 1. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11849,18 +11724,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC3 (`INT32`) {#VOXL2_IO_FUNC3} - -VOXL2 IO Output PWM Channel 3 Output Function. +### VTQ_IO_FUNC10 (`INT32`) {#VTQ_IO_FUNC10} -Select what should be output on VOXL2 IO Output PWM Channel 3. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 10 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 10. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11920,18 +11788,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC4 (`INT32`) {#VOXL2_IO_FUNC4} - -VOXL2 IO Output PWM Channel 4 Output Function. +### VTQ_IO_FUNC11 (`INT32`) {#VTQ_IO_FUNC11} -Select what should be output on VOXL2 IO Output PWM Channel 4. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 11 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 11. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -11991,18 +11852,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC5 (`INT32`) {#VOXL2_IO_FUNC5} - -VOXL2 IO Output PWM Channel 5 Output Function. +### VTQ_IO_FUNC12 (`INT32`) {#VTQ_IO_FUNC12} -Select what should be output on VOXL2 IO Output PWM Channel 5. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 12 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 12. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12062,18 +11916,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC6 (`INT32`) {#VOXL2_IO_FUNC6} - -VOXL2 IO Output PWM Channel 6 Output Function. +### VTQ_IO_FUNC13 (`INT32`) {#VTQ_IO_FUNC13} -Select what should be output on VOXL2 IO Output PWM Channel 6. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 13 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 13. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12133,18 +11980,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC7 (`INT32`) {#VOXL2_IO_FUNC7} - -VOXL2 IO Output PWM Channel 7 Output Function. +### VTQ_IO_FUNC14 (`INT32`) {#VTQ_IO_FUNC14} -Select what should be output on VOXL2 IO Output PWM Channel 7. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 14 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 14. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12204,18 +12044,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_FUNC8 (`INT32`) {#VOXL2_IO_FUNC8} - -VOXL2 IO Output PWM Channel 8 Output Function. +### VTQ_IO_FUNC15 (`INT32`) {#VTQ_IO_FUNC15} -Select what should be output on VOXL2 IO Output PWM Channel 8. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 15 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 15. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12275,40 +12108,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL2_IO_REV (`INT32`) {#VOXL2_IO_REV} - -Reverse Output Range for VOXL2 IO Output. - -Allows to reverse the output range for each channel. -Note: this is only useful for servos. - -**Bitmask:** - -- `0`: VOXL2 IO Output PWM Channel 1 -- `1`: VOXL2 IO Output PWM Channel 2 -- `2`: VOXL2 IO Output PWM Channel 3 -- `3`: VOXL2 IO Output PWM Channel 4 -- `4`: VOXL2 IO Output PWM Channel 5 -- `5`: VOXL2 IO Output PWM Channel 6 -- `6`: VOXL2 IO Output PWM Channel 7 -- `7`: VOXL2 IO Output PWM Channel 8 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 255 | | 0 | - -### VOXL_ESC_FUNC1 (`INT32`) {#VOXL_ESC_FUNC1} - -VOXL ESC Output ESC 1 Output Function. +### VTQ_IO_FUNC2 (`INT32`) {#VTQ_IO_FUNC2} -Select what should be output on VOXL ESC Output ESC 1. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 2 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 2. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12368,18 +12172,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL_ESC_FUNC2 (`INT32`) {#VOXL_ESC_FUNC2} - -VOXL ESC Output ESC 2 Output Function. +### VTQ_IO_FUNC3 (`INT32`) {#VTQ_IO_FUNC3} -Select what should be output on VOXL ESC Output ESC 2. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 3 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 3. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12439,18 +12236,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL_ESC_FUNC3 (`INT32`) {#VOXL_ESC_FUNC3} - -VOXL ESC Output ESC 3 Output Function. +### VTQ_IO_FUNC4 (`INT32`) {#VTQ_IO_FUNC4} -Select what should be output on VOXL ESC Output ESC 3. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 4 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 4. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12510,18 +12300,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL_ESC_FUNC4 (`INT32`) {#VOXL_ESC_FUNC4} - -VOXL ESC Output ESC 4 Output Function. +### VTQ_IO_FUNC5 (`INT32`) {#VTQ_IO_FUNC5} -Select what should be output on VOXL ESC Output ESC 4. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 5 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 5. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -12581,388 +12364,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VOXL_ESC_REV (`INT32`) {#VOXL_ESC_REV} - -Reverse Output Range for VOXL ESC Output. - -Allows to reverse the output range for each channel. -Note: this is only useful for servos. - -**Bitmask:** - -- `0`: VOXL ESC Output ESC 1 -- `1`: VOXL ESC Output ESC 2 -- `2`: VOXL ESC Output ESC 3 -- `3`: VOXL ESC Output ESC 4 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | | 0 | - -### VTQ_IO_DIS0 (`INT32`) {#VTQ_IO_DIS0} - -Vertiq IO CVI 0 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS1 (`INT32`) {#VTQ_IO_DIS1} - -Vertiq IO CVI 1 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS10 (`INT32`) {#VTQ_IO_DIS10} - -Vertiq IO CVI 10 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS11 (`INT32`) {#VTQ_IO_DIS11} - -Vertiq IO CVI 11 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS12 (`INT32`) {#VTQ_IO_DIS12} - -Vertiq IO CVI 12 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS13 (`INT32`) {#VTQ_IO_DIS13} - -Vertiq IO CVI 13 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS14 (`INT32`) {#VTQ_IO_DIS14} - -Vertiq IO CVI 14 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS15 (`INT32`) {#VTQ_IO_DIS15} - -Vertiq IO CVI 15 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS2 (`INT32`) {#VTQ_IO_DIS2} - -Vertiq IO CVI 2 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS3 (`INT32`) {#VTQ_IO_DIS3} - -Vertiq IO CVI 3 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS4 (`INT32`) {#VTQ_IO_DIS4} - -Vertiq IO CVI 4 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS5 (`INT32`) {#VTQ_IO_DIS5} - -Vertiq IO CVI 5 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS6 (`INT32`) {#VTQ_IO_DIS6} - -Vertiq IO CVI 6 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS7 (`INT32`) {#VTQ_IO_DIS7} - -Vertiq IO CVI 7 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS8 (`INT32`) {#VTQ_IO_DIS8} - -Vertiq IO CVI 8 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_DIS9 (`INT32`) {#VTQ_IO_DIS9} - -Vertiq IO CVI 9 Disarmed Value. - -This is the output value that is set when not armed. -Note that non-motor outputs might already be active in prearm state if COM_PREARM_MODE is set. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 0 | - -### VTQ_IO_FAIL0 (`INT32`) {#VTQ_IO_FAIL0} - -Vertiq IO CVI 0 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC0). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL1 (`INT32`) {#VTQ_IO_FAIL1} - -Vertiq IO CVI 1 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC1). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL10 (`INT32`) {#VTQ_IO_FAIL10} - -Vertiq IO CVI 10 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC10). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL11 (`INT32`) {#VTQ_IO_FAIL11} - -Vertiq IO CVI 11 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC11). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL12 (`INT32`) {#VTQ_IO_FAIL12} - -Vertiq IO CVI 12 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC12). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL13 (`INT32`) {#VTQ_IO_FAIL13} - -Vertiq IO CVI 13 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC13). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL14 (`INT32`) {#VTQ_IO_FAIL14} - -Vertiq IO CVI 14 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC14). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL15 (`INT32`) {#VTQ_IO_FAIL15} - -Vertiq IO CVI 15 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC15). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL2 (`INT32`) {#VTQ_IO_FAIL2} - -Vertiq IO CVI 2 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC2). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL3 (`INT32`) {#VTQ_IO_FAIL3} - -Vertiq IO CVI 3 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC3). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL4 (`INT32`) {#VTQ_IO_FAIL4} - -Vertiq IO CVI 4 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC4). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL5 (`INT32`) {#VTQ_IO_FAIL5} - -Vertiq IO CVI 5 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC5). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL6 (`INT32`) {#VTQ_IO_FAIL6} - -Vertiq IO CVI 6 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC6). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL7 (`INT32`) {#VTQ_IO_FAIL7} - -Vertiq IO CVI 7 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC7). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL8 (`INT32`) {#VTQ_IO_FAIL8} - -Vertiq IO CVI 8 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC8). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FAIL9 (`INT32`) {#VTQ_IO_FAIL9} - -Vertiq IO CVI 9 Failsafe Value. - -This is the output value that is set when in failsafe mode. -When set to -1 (default), the value depends on the function (see VTQ_IO_FUNC9). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 500 | | -1 | - -### VTQ_IO_FUNC0 (`INT32`) {#VTQ_IO_FUNC0} - -Vertiq IO CVI 0 Output Function. +### VTQ_IO_FUNC6 (`INT32`) {#VTQ_IO_FUNC6} -Select what should be output on Vertiq IO CVI 0. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 6 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 6. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -13022,18 +12428,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VTQ_IO_FUNC1 (`INT32`) {#VTQ_IO_FUNC1} - -Vertiq IO CVI 1 Output Function. +### VTQ_IO_FUNC7 (`INT32`) {#VTQ_IO_FUNC7} -Select what should be output on Vertiq IO CVI 1. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 7 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 7. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -13093,18 +12492,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VTQ_IO_FUNC10 (`INT32`) {#VTQ_IO_FUNC10} - -Vertiq IO CVI 10 Output Function. +### VTQ_IO_FUNC8 (`INT32`) {#VTQ_IO_FUNC8} -Select what should be output on Vertiq IO CVI 10. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 8 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 8. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -13164,18 +12556,11 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VTQ_IO_FUNC11 (`INT32`) {#VTQ_IO_FUNC11} - -Vertiq IO CVI 11 Output Function. +### VTQ_IO_FUNC9 (`INT32`) {#VTQ_IO_FUNC9} -Select what should be output on Vertiq IO CVI 11. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 9 Output Function. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +Select what should be output on Vertiq IO CVI 9. The default failsafe value is set according to the selected function: - 'Min' for ConstantMin - 'Max' for ConstantMax - 'Max' for Parachute - ('Max'+'Min')/2 for Servos - 'Disarmed' for the rest **Values:** @@ -13235,903 +12620,51 @@ The default failsafe value is set according to the selected function: | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### VTQ_IO_FUNC12 (`INT32`) {#VTQ_IO_FUNC12} +### VTQ_IO_MAX0 (`INT32`) {#VTQ_IO_MAX0} -Vertiq IO CVI 12 Output Function. +Vertiq IO CVI 0 Maximum Value. -Select what should be output on Vertiq IO CVI 12. -The default failsafe value is set according to the selected function: +Maxmimum output value (when not disarmed). -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 65535 | | 65535 | -**Values:** +### VTQ_IO_MAX1 (`INT32`) {#VTQ_IO_MAX1} -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter +Vertiq IO CVI 1 Maximum Value. + +Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0 | 65535 | | 65535 | -### VTQ_IO_FUNC13 (`INT32`) {#VTQ_IO_FUNC13} +### VTQ_IO_MAX10 (`INT32`) {#VTQ_IO_MAX10} -Vertiq IO CVI 13 Output Function. +Vertiq IO CVI 10 Maximum Value. -Select what should be output on Vertiq IO CVI 13. -The default failsafe value is set according to the selected function: +Maxmimum output value (when not disarmed). + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 65535 | | 65535 | -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest +### VTQ_IO_MAX11 (`INT32`) {#VTQ_IO_MAX11} -**Values:** +Vertiq IO CVI 11 Maximum Value. -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter +Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC14 (`INT32`) {#VTQ_IO_FUNC14} +|   | 0 | 65535 | | 65535 | -Vertiq IO CVI 14 Output Function. +### VTQ_IO_MAX12 (`INT32`) {#VTQ_IO_MAX12} -Select what should be output on Vertiq IO CVI 14. -The default failsafe value is set according to the selected function: +Vertiq IO CVI 12 Maximum Value. -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC15 (`INT32`) {#VTQ_IO_FUNC15} - -Vertiq IO CVI 15 Output Function. - -Select what should be output on Vertiq IO CVI 15. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC2 (`INT32`) {#VTQ_IO_FUNC2} - -Vertiq IO CVI 2 Output Function. - -Select what should be output on Vertiq IO CVI 2. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC3 (`INT32`) {#VTQ_IO_FUNC3} - -Vertiq IO CVI 3 Output Function. - -Select what should be output on Vertiq IO CVI 3. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC4 (`INT32`) {#VTQ_IO_FUNC4} - -Vertiq IO CVI 4 Output Function. - -Select what should be output on Vertiq IO CVI 4. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC5 (`INT32`) {#VTQ_IO_FUNC5} - -Vertiq IO CVI 5 Output Function. - -Select what should be output on Vertiq IO CVI 5. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC6 (`INT32`) {#VTQ_IO_FUNC6} - -Vertiq IO CVI 6 Output Function. - -Select what should be output on Vertiq IO CVI 6. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC7 (`INT32`) {#VTQ_IO_FUNC7} - -Vertiq IO CVI 7 Output Function. - -Select what should be output on Vertiq IO CVI 7. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC8 (`INT32`) {#VTQ_IO_FUNC8} - -Vertiq IO CVI 8 Output Function. - -Select what should be output on Vertiq IO CVI 8. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_FUNC9 (`INT32`) {#VTQ_IO_FUNC9} - -Vertiq IO CVI 9 Output Function. - -Select what should be output on Vertiq IO CVI 9. -The default failsafe value is set according to the selected function: - -- 'Min' for ConstantMin -- 'Max' for ConstantMax -- 'Max' for Parachute -- ('Max'+'Min')/2 for Servos -- 'Disarmed' for the rest - -**Values:** - -- `0`: Disabled -- `1`: Constant Min -- `2`: Constant Max -- `101`: Motor 1 -- `102`: Motor 2 -- `103`: Motor 3 -- `104`: Motor 4 -- `105`: Motor 5 -- `106`: Motor 6 -- `107`: Motor 7 -- `108`: Motor 8 -- `109`: Motor 9 -- `110`: Motor 10 -- `111`: Motor 11 -- `112`: Motor 12 -- `201`: Servo 1 -- `202`: Servo 2 -- `203`: Servo 3 -- `204`: Servo 4 -- `205`: Servo 5 -- `206`: Servo 6 -- `207`: Servo 7 -- `208`: Servo 8 -- `301`: Peripheral via Actuator Set 1 -- `302`: Peripheral via Actuator Set 2 -- `303`: Peripheral via Actuator Set 3 -- `304`: Peripheral via Actuator Set 4 -- `305`: Peripheral via Actuator Set 5 -- `306`: Peripheral via Actuator Set 6 -- `400`: Landing Gear -- `401`: Parachute -- `402`: RC Roll -- `403`: RC Pitch -- `404`: RC Throttle -- `405`: RC Yaw -- `406`: RC Flaps -- `407`: RC AUX 1 -- `408`: RC AUX 2 -- `409`: RC AUX 3 -- `410`: RC AUX 4 -- `411`: RC AUX 5 -- `412`: RC AUX 6 -- `420`: Gimbal Roll -- `421`: Gimbal Pitch -- `422`: Gimbal Yaw -- `430`: Gripper -- `440`: Landing Gear Wheel -- `450`: IC Engine Ignition -- `451`: IC Engine Throttle -- `452`: IC Engine Choke -- `453`: IC Engine Starter - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VTQ_IO_MAX0 (`INT32`) {#VTQ_IO_MAX0} - -Vertiq IO CVI 0 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 65535 | - -### VTQ_IO_MAX1 (`INT32`) {#VTQ_IO_MAX1} - -Vertiq IO CVI 1 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 65535 | - -### VTQ_IO_MAX10 (`INT32`) {#VTQ_IO_MAX10} - -Vertiq IO CVI 10 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 65535 | - -### VTQ_IO_MAX11 (`INT32`) {#VTQ_IO_MAX11} - -Vertiq IO CVI 11 Maximum Value. - -Maxmimum output value (when not disarmed). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | | 65535 | - -### VTQ_IO_MAX12 (`INT32`) {#VTQ_IO_MAX12} - -Vertiq IO CVI 12 Maximum Value. - -Maxmimum output value (when not disarmed). +Maxmimum output value (when not disarmed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -14411,8 +12944,7 @@ Minimum output value (when not disarmed). Reverse Output Range for Vertiq IO. -Allows to reverse the output range for each channel. -Note: this is only useful for servos. +Allows to reverse the output range for each channel. Note: this is only useful for servos. **Bitmask:** @@ -14464,7 +12996,6 @@ Sideslip measurement noise of the internal wind estimator(s) of the airspeed sel Enable checks on airspeed sensors. Controls which checks are run to check airspeed data for validity. Only applied if ASPD_PRIMARY > 0. -Note: The missing data check (bit 0) is implicitly always enabled when ASPD_DO_CHECKS > 0, even if bit 0 is not explicitly set. **Bitmask:** @@ -14496,11 +13027,7 @@ Fallback options. First principle airspeed check time window. -Window for comparing airspeed change to throttle and pitch change. -Triggers when the airspeed change within this window is negative while throttle increases -and the vehicle pitches down. -Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. -Relies on FW_THR_TRIM being set accurately. +Window for comparing airspeed change to throttle and pitch change. Triggers when the airspeed change within this window is negative while throttle increases and the vehicle pitches down. Is meant to catch degrading airspeed blockages as can happen when flying through icing conditions. Relies on FW_THR_TRIM being set accurately. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -14510,10 +13037,7 @@ Relies on FW_THR_TRIM being set accurately. Airspeed failure innovation threshold. -This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, -smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) -and measured airspeed. -The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. +This specifies the minimum airspeed innovation required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Large innovations indicate an inconsistency between predicted (groundspeed - windspeeed) and measured airspeed. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -14523,8 +13047,7 @@ The time required to detect a fault when the threshold is exceeded depends on th Airspeed failure innovation integral threshold. -This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. -Larger values make the check less sensitive, smaller positive values make it more sensitive. +This sets the time integral of airspeed innovation exceedance above ASPD_FS_INNOV required to trigger a failsafe. Larger values make the check less sensitive, smaller positive values make it more sensitive. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -14534,8 +13057,7 @@ Larger values make the check less sensitive, smaller positive values make it mor Airspeed failsafe start delay. -Delay before switching back to using airspeed sensor if checks indicate sensor is good. -Set to a negative value to disable the re-enabling in flight. +Delay before switching back to using airspeed sensor if checks indicate sensor is good. Set to a negative value to disable the re-enabling in flight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -14573,9 +13095,9 @@ Scale of airspeed sensor 1. This is the scale IAS --> CAS of the first airspeed sensor instance -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.5 | 2.0 | | 1.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0.5 | 2.0 | | 1.0 | ### ASPD_SCALE_2 (`FLOAT`) {#ASPD_SCALE_2} @@ -14583,9 +13105,9 @@ Scale of airspeed sensor 2. This is the scale IAS --> CAS of the second airspeed sensor instance -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.5 | 2.0 | | 1.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0.5 | 2.0 | | 1.0 | ### ASPD_SCALE_3 (`FLOAT`) {#ASPD_SCALE_3} @@ -14593,9 +13115,9 @@ Scale of airspeed sensor 3. This is the scale IAS --> CAS of the third airspeed sensor instance -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.5 | 2.0 | | 1.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0.5 | 2.0 | | 1.0 | ### ASPD_SCALE_APPLY (`INT32`) {#ASPD_SCALE_APPLY} @@ -14615,8 +13137,7 @@ Controls when to apply the new estimated airspeed scale(s). Wind estimator true airspeed scale process noise spectral density. -Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. -When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second. +Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the scale uncertainty (1-sigma, unitless) increases by this amount every second. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------------ | @@ -14644,21 +13165,19 @@ True airspeed measurement noise of the internal wind estimator(s) of the airspee ### ASPD_WERR_THR (`FLOAT`) {#ASPD_WERR_THR} -Horizontal wind uncertainty threshold for valid ground-minus-wind. +Horizontal wind uncertainty threshold for synthetic airspeed. -The airspeed alternative derived from groundspeed and heading will be declared valid -as soon and as long the horizontal wind uncertainty is below this value. +The synthetic airspeed estimate (from groundspeed and heading) will be declared valid as soon and as long the horizontal wind uncertainty is below this value. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 5 | | 2. | m/s | +|   | 0.001 | 5 | | 0.55 | m/s | ### ASPD_WIND_NSD (`FLOAT`) {#ASPD_WIND_NSD} Wind estimator wind process noise spectral density. -Wind process noise of the internal wind estimator(s) of the airspeed selector. -When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. +Wind process noise of the internal wind estimator(s) of the airspeed selector. When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases by this amount every second. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | -------------- | @@ -14696,8 +13215,7 @@ Enable standalone quaternion based attitude estimator. External heading usage mode (from Motion capture/Vision). -Set to 1 to use heading estimate from vision. -Set to 2 to use heading from motion capture. +Set to 1 to use heading estimate from vision. Set to 2 to use heading from motion capture. **Values:** @@ -14713,9 +13231,7 @@ Set to 2 to use heading from motion capture. Magnetic declination, in degrees. -This parameter is not used in normal operation, -as the declination is looked up based on the -GPS coordinates of the vehicle. +This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -14769,9 +13285,7 @@ Set to 0 to avoid using the magnetometer. Controls when to apply the new gains. -After the auto-tuning sequence is completed, -a new set of gains is available and can be applied -immediately or after landing. +After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. **Values:** @@ -14787,11 +13301,7 @@ immediately or after landing. Tuning axes selection. -Defines which axes will be tuned during the auto-tuning sequence -Set bits in the following positions to enable: -0 : Roll -1 : Pitch -2 : Yaw +Defines which axes will be tuned during the auto-tuning sequence Set bits in the following positions to enable: 0 : Roll 1 : Pitch 2 : Yaw **Bitmask:** @@ -14805,9 +13315,9 @@ Set bits in the following positions to enable: ### FW_AT_MAN_AUX (`INT32`) {#FW_AT_MAN_AUX} -Enable/disable auto tuning using a manual control AUX input. +Enable/disable auto tuning using an RC AUX input. -Defines which RC_MAP_AUXn parameter maps the manual control channel used to enable/disable auto tuning. +Defines which RC_MAP_AUXn parameter maps the RC channel used to enable/disable auto tuning. **Values:** @@ -14823,6 +13333,26 @@ Defines which RC_MAP_AUXn parameter maps the manual control channel used to enab | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 6 | | 0 | +### FW_AT_START (`INT32`) {#FW_AT_START} + +Start the autotuning sequence. + +WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using FW_AT_SYSID_AMP for more signal/noise ratio + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | + +### FW_AT_SYSID_AMP (`FLOAT`) {#FW_AT_SYSID_AMP} + +Amplitude of the injected signal. + +This parameter scales the signal sent to the rate controller during system identification. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 6.0 | | 1.0 | + ### FW_AT_SYSID_F0 (`FLOAT`) {#FW_AT_SYSID_F0} Start frequency of the injected signal. @@ -14841,7 +13371,7 @@ Can be set lower or higher than the start frequency | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 30.0 | | 10. | Hz | +|   | 0.1 | 30.0 | | 20. | Hz | ### FW_AT_SYSID_TIME (`FLOAT`) {#FW_AT_SYSID_TIME} @@ -14867,18 +13397,13 @@ Type of signal used during system identification to excite the system. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 1 | +|   | | | | 0 | ### MC_AT_APPLY (`INT32`) {#MC_AT_APPLY} Controls when to apply the new gains. -After the auto-tuning sequence is completed, -a new set of gains is available and can be applied -immediately or after landing. -WARNING Applying the gains in air is dangerous as there is no -guarantee that those new gains will be able to stabilize -the drone properly. +After the auto-tuning sequence is completed, a new set of gains is available and can be applied immediately or after landing. WARNING Applying the gains in air is dangerous as there is no guarantee that those new gains will be able to stabilize the drone properly. **Values:** @@ -14906,6 +13431,16 @@ Desired angular rate closed-loop rise time. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.01 | 0.5 | | 0.14 | s | +### MC_AT_START (`INT32`) {#MC_AT_START} + +Start the autotuning sequence. + +WARNING: this will inject steps to the rate controller and can be dangerous. Only activate if you know what you are doing, and in a safe environment. Any motion of the remote stick will abort the signal injection and reset this parameter Best is to perform the identification in position or hold mode. Increase the amplitude of the injected signal using MC_AT_SYSID_AMP for more signal/noise ratio + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | + ### MC_AT_SYSID_AMP (`FLOAT`) {#MC_AT_SYSID_AMP} Amplitude of the injected signal. @@ -14920,9 +13455,7 @@ Amplitude of the injected signal. Battery 1 current per volt (A/V). -The voltage seen by the ADC multiplied by this factor -will determine the battery current. A value of -1 means to use -the board default. +The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -14942,8 +13475,7 @@ Defines the capacity of battery 1 in mAh. Battery 1 Current ADC Channel. -This parameter specifies the ADC channel used to monitor current of main power battery. -A value of -1 means to use the board default. +This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -14953,13 +13485,7 @@ A value of -1 means to use the board default. Battery 1 idle current overwrite. -This parameter allows to overwrite the current measured during -idle (unarmed) state with a user-defined constant value (expressed in amperes). -When the system is armed, the measured current is used. This is useful -because on certain ESCs current measurements are inaccurate in case of no load. -Negative values are ignored and will cause the measured current to be used. -The default value of 0 disables the overwrite, in which case the measured value -is always used. +This parameter allows to overwrite the current measured during idle (unarmed) state with a user-defined constant value (expressed in amperes). When the system is armed, the measured current is used. This is useful because on certain ESCs current measurements are inaccurate in case of no load. Negative values are ignored and will cause the measured current to be used. The default value of 0 disables the overwrite, in which case the measured value is always used. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15009,21 +13535,12 @@ If non-negative, then this will be used instead of the online estimated internal Battery 1 monitoring source. -This parameter controls the source of battery data. The value 'Power Module / Analog' -means that measurements are expected to come from either analog (ADC) inputs -or an I2C power monitor (e.g. INA226). Analog inputs are voltage and current -measurements read from the board's ADC channels, typically from an onboard -voltage divider and current shunt, or an external analog power module. -I2C power monitors are digital sensors on the I2C bus. -If the value is set to 'External' then the system expects to receive MAVLink -or CAN battery status messages, or the battery data is published by an external driver. -If the value is set to 'ESCs', the battery information are taken from the esc_status message. -This requires the ESC to provide both voltage as well as current (via ESC telemetry). +This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. **Values:** - `-1`: Disabled -- `0`: Power Module / Analog +- `0`: Power Module - `1`: External - `2`: ESCs @@ -15035,10 +13552,7 @@ This requires the ESC to provide both voltage as well as current (via ESC teleme Battery 1 Voltage ADC Channel. -This parameter specifies the ADC channel used to monitor voltage of main power battery. -A value of -1 means to use the board default. A value of -2 disables analog monitoring. -This is useful when the FMU supports both analog and digital voltage monitoring and you want -to use digital monitoring exclusively. +This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15048,8 +13562,7 @@ to use digital monitoring exclusively. Full cell voltage. -Defines the voltage where a single cell of the battery is considered full. -For a more accurate estimate set this below the nominal voltage of e.g. 4.2V +Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15059,10 +13572,7 @@ For a more accurate estimate set this below the nominal voltage of e.g. 4.2V Battery 1 voltage divider (V divider). -This is the divider from battery 1 voltage to ADC voltage. -If using e.g. Mauch power modules the value from the datasheet -can be applied straight here. A value of -1 means to use -the board default. +This is the divider from battery 1 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15072,10 +13582,7 @@ the board default. Empty cell voltage. -Defines the voltage where a single cell of the battery is considered empty. -The voltage should be chosen above the steep dropoff at 3.5V. A typical -lithium battery can only be discharged under high load down to 10% before -it drops off to a voltage level damaging the cells. +Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15085,9 +13592,7 @@ it drops off to a voltage level damaging the cells. Battery 2 current per volt (A/V). -The voltage seen by the ADC multiplied by this factor -will determine the battery current. A value of -1 means to use -the board default. +The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15107,8 +13612,7 @@ Defines the capacity of battery 2 in mAh. Battery 2 Current ADC Channel. -This parameter specifies the ADC channel used to monitor current of main power battery. -A value of -1 means to use the board default. +This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15118,13 +13622,7 @@ A value of -1 means to use the board default. Battery 2 idle current overwrite. -This parameter allows to overwrite the current measured during -idle (unarmed) state with a user-defined constant value (expressed in amperes). -When the system is armed, the measured current is used. This is useful -because on certain ESCs current measurements are inaccurate in case of no load. -Negative values are ignored and will cause the measured current to be used. -The default value of 0 disables the overwrite, in which case the measured value -is always used. +This parameter allows to overwrite the current measured during idle (unarmed) state with a user-defined constant value (expressed in amperes). When the system is armed, the measured current is used. This is useful because on certain ESCs current measurements are inaccurate in case of no load. Negative values are ignored and will cause the measured current to be used. The default value of 0 disables the overwrite, in which case the measured value is always used. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15174,21 +13672,12 @@ If non-negative, then this will be used instead of the online estimated internal Battery 2 monitoring source. -This parameter controls the source of battery data. The value 'Power Module / Analog' -means that measurements are expected to come from either analog (ADC) inputs -or an I2C power monitor (e.g. INA226). Analog inputs are voltage and current -measurements read from the board's ADC channels, typically from an onboard -voltage divider and current shunt, or an external analog power module. -I2C power monitors are digital sensors on the I2C bus. -If the value is set to 'External' then the system expects to receive MAVLink -or CAN battery status messages, or the battery data is published by an external driver. -If the value is set to 'ESCs', the battery information are taken from the esc_status message. -This requires the ESC to provide both voltage as well as current (via ESC telemetry). +This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. **Values:** - `-1`: Disabled -- `0`: Power Module / Analog +- `0`: Power Module - `1`: External - `2`: ESCs @@ -15200,10 +13689,7 @@ This requires the ESC to provide both voltage as well as current (via ESC teleme Battery 2 Voltage ADC Channel. -This parameter specifies the ADC channel used to monitor voltage of main power battery. -A value of -1 means to use the board default. A value of -2 disables analog monitoring. -This is useful when the FMU supports both analog and digital voltage monitoring and you want -to use digital monitoring exclusively. +This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15213,8 +13699,7 @@ to use digital monitoring exclusively. Full cell voltage. -Defines the voltage where a single cell of the battery is considered full. -For a more accurate estimate set this below the nominal voltage of e.g. 4.2V +Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15224,10 +13709,7 @@ For a more accurate estimate set this below the nominal voltage of e.g. 4.2V Battery 2 voltage divider (V divider). -This is the divider from battery 2 voltage to ADC voltage. -If using e.g. Mauch power modules the value from the datasheet -can be applied straight here. A value of -1 means to use -the board default. +This is the divider from battery 2 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15237,10 +13719,7 @@ the board default. Empty cell voltage. -Defines the voltage where a single cell of the battery is considered empty. -The voltage should be chosen above the steep dropoff at 3.5V. A typical -lithium battery can only be discharged under high load down to 10% before -it drops off to a voltage level damaging the cells. +Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15300,21 +13779,12 @@ If non-negative, then this will be used instead of the online estimated internal Battery 3 monitoring source. -This parameter controls the source of battery data. The value 'Power Module / Analog' -means that measurements are expected to come from either analog (ADC) inputs -or an I2C power monitor (e.g. INA226). Analog inputs are voltage and current -measurements read from the board's ADC channels, typically from an onboard -voltage divider and current shunt, or an external analog power module. -I2C power monitors are digital sensors on the I2C bus. -If the value is set to 'External' then the system expects to receive MAVLink -or CAN battery status messages, or the battery data is published by an external driver. -If the value is set to 'ESCs', the battery information are taken from the esc_status message. -This requires the ESC to provide both voltage as well as current (via ESC telemetry). +This parameter controls the source of battery data. The value 'Power Module' means that measurements are expected to come from a power module. If the value is set to 'External' then the system expects to receive mavlink battery status messages. If the value is set to 'ESCs', the battery information are taken from the esc_status message. This requires the ESC to provide both voltage as well as current. **Values:** - `-1`: Disabled -- `0`: Power Module / Analog +- `0`: Power Module - `1`: External - `2`: ESCs @@ -15326,8 +13796,7 @@ This requires the ESC to provide both voltage as well as current (via ESC teleme Full cell voltage. -Defines the voltage where a single cell of the battery is considered full. -For a more accurate estimate set this below the nominal voltage of e.g. 4.2V +Defines the voltage where a single cell of the battery is considered full. For a more accurate estimate set this below the nominal voltage of e.g. 4.2V | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15337,10 +13806,7 @@ For a more accurate estimate set this below the nominal voltage of e.g. 4.2V Empty cell voltage. -Defines the voltage where a single cell of the battery is considered empty. -The voltage should be chosen above the steep dropoff at 3.5V. A typical -lithium battery can only be discharged under high load down to 10% before -it drops off to a voltage level damaging the cells. +Defines the voltage where a single cell of the battery is considered empty. The voltage should be chosen above the steep dropoff at 3.5V. A typical lithium battery can only be discharged under high load down to 10% before it drops off to a voltage level damaging the cells. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15358,8 +13824,7 @@ This parameter is deprecated. Please use BAT1_I_CHANNEL. Expected battery current in flight. -This value is used to initialize the in-flight average current estimation, -which in turn is used for estimating remaining flight time and RTL triggering. +This value is used to initialize the in-flight average current estimation, which in turn is used for estimating remaining flight time and RTL triggering. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15369,9 +13834,7 @@ which in turn is used for estimating remaining flight time and RTL triggering. Critical threshold. -Sets the threshold when the battery will be reported as critically low. -This has to be lower than the low threshold. This threshold commonly -will trigger RTL. +Sets the threshold when the battery will be reported as critically low. This has to be lower than the low threshold. This threshold commonly will trigger RTL. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15381,9 +13844,7 @@ will trigger RTL. Emergency threshold. -Sets the threshold when the battery will be reported as dangerously low. -This has to be lower than the critical threshold. This threshold commonly -will trigger landing. +Sets the threshold when the battery will be reported as dangerously low. This has to be lower than the critical threshold. This threshold commonly will trigger landing. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15393,8 +13854,7 @@ will trigger landing. Low threshold. -Sets the threshold when the battery will be reported as low. -This has to be higher than the critical threshold. +Sets the threshold when the battery will be reported as low. This has to be higher than the critical threshold. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15404,8 +13864,7 @@ This has to be higher than the critical threshold. Offset in volt as seen by the ADC input of the current sensor. -This offset will be subtracted before calculating the battery -current based on the voltage. +This offset will be subtracted before calculating the battery current based on the voltage. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15446,7 +13905,6 @@ Specify USB MAVLink mode. - `10`: gimbal - `11`: onboard_low_bandwidth - `12`: uavionix -- `13`: Low Bandwidth | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15558,8 +14016,7 @@ This parameter sets the time between two consecutive trigger events Minimum camera trigger interval. -This parameter sets the minimum time between two consecutive trigger events -the specific camera setup is supporting. +This parameter sets the minimum time between two consecutive trigger events the specific camera setup is supporting. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15618,9 +14075,7 @@ PWM output to trigger shot. Circuit breaker for disabling buzzer. -Setting this parameter to 782097 will disable the buzzer audio notification. -Setting this parameter to 782090 will disable the startup tune, while keeping -all others enabled. +Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15630,10 +14085,7 @@ all others enabled. Circuit breaker for flight termination. -Setting this parameter to 121212 will disable the flight termination action if triggered -by the FailureDetector logic or if FMU is lost. -This circuit breaker does not affect the RC loss, data link loss, geofence, -and takeoff failure detection safety logic. +Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -15643,8 +14095,7 @@ and takeoff failure detection safety logic. Circuit breaker for IO safety. -Setting this parameter to 22027 will disable IO safety. -WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK +Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15654,9 +14105,7 @@ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Circuit breaker for power supply check. -Setting this parameter to 894281 will disable the power valid -checks in the commander. -WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK +Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15666,12 +14115,7 @@ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Circuit breaker for USB link check. -Setting this parameter to 197848 will disable the USB connected -checks in the commander, setting it to 0 keeps them enabled (recommended). -We are generally recommending to not fly with the USB link -connected and production vehicles should set this parameter to -zero to prevent users from flying USB powered. However, for R&D purposes -it has proven over the years to work just fine. +Setting this parameter to 197848 will disable the USB connected checks in the commander, setting it to 0 keeps them enabled (recommended). We are generally recommending to not fly with the USB link connected and production vehicles should set this parameter to zero to prevent users from flying USB powered. However, for R&D purposes it has proven over the years to work just fine. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15681,9 +14125,7 @@ it has proven over the years to work just fine. Circuit breaker for arming in fixed-wing mode check. -Setting this parameter to 159753 will enable arming in fixed-wing -mode for VTOLs. -WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK +Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15695,8 +14137,7 @@ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK Set the actuator failure failsafe mode. -Note: actuator failure needs to be enabled and configured via FD*ACT*\* -parameters. +Note: actuator failure needs to be enabled and configured via FD*ACT*\* parameters. **Values:** @@ -15739,12 +14180,7 @@ Used if arm authorization is requested by COM_ARM_AUTH_REQ. Arm authorization method. -Methods: - -- one arm: request authorization and arm when authorization is received -- two step arm: 1st arm command request an authorization and - 2nd arm command arm the drone if authorized - Used if arm authorization is requested by COM_ARM_AUTH_REQ. +Methods: - one arm: request authorization and arm when authorization is received - two step arm: 1st arm command request an authorization and 2nd arm command arm the drone if authorized Used if arm authorization is requested by COM_ARM_AUTH_REQ. **Values:** @@ -15769,8 +14205,7 @@ By default off. The default allows to arm the vehicle without a arm authorizatio Arm authorization timeout. -Timeout for authorizer answer. -Used if arm authorization is requested by COM_ARM_AUTH_REQ. +Timeout for authorizer answer. Used if arm authorization is requested by COM_ARM_AUTH_REQ. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15780,8 +14215,7 @@ Used if arm authorization is requested by COM_ARM_AUTH_REQ. Minimum battery level for arming. -Threshold for battery percentage below arming is prohibited. -A negative value means BAT_CRIT_THR is the threshold. +Threshold for battery percentage below arming is prohibited. A negative value means BAT_CRIT_THR is the threshold. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15791,8 +14225,7 @@ A negative value means BAT_CRIT_THR is the threshold. Enable checks on ESCs that report telemetry. -If this parameter is set, the system will check ESC's online status and failures. -This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry. +If this parameter is set, the system will check ESC's online status and failures. This param is specific for ESCs reporting status. It shall be used only if ESCs support telemetry. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -15802,8 +14235,7 @@ This param is specific for ESCs reporting status. It shall be used only if ESCs Enable FMU SD card hardfault detection check. -This check detects if there are hardfault files present on the -SD card. If so, and the parameter is enabled, arming is prevented. +This check detects if there are hardfault files present on the SD card. If so, and the parameter is enabled, arming is prevented. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -15839,8 +14271,7 @@ Set -1 to disable the check. Enable mag strength preflight check. -Check if the estimator detects a strong magnetic -disturbance (check enabled by EKF2_MAG_CHECK) +Check if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK) **Values:** @@ -15866,9 +14297,7 @@ The default allows to arm the vehicle without a valid mission. Enable Drone ID system detection and health check. -This check detects if the Open Drone ID system is missing. -Depending on the value of the parameter, the check can be -disabled, warn only or deny arming. +This check detects if the Open Drone ID system is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. **Values:** @@ -15884,9 +14313,7 @@ disabled, warn only or deny arming. Enable FMU SD card detection check. -This check detects if the FMU SD card is missing. -Depending on the value of the parameter, the check can be -disabled, warn only or deny arming. +This check detects if the FMU SD card is missing. Depending on the value of the parameter, the check can be disabled, warn only or deny arming. **Values:** @@ -15902,8 +14329,7 @@ disabled, warn only or deny arming. Arm switch is a momentary button. -0: Arming/disarming triggers on switch transition. -1: Arming/disarming triggers when holding the momentary button down like the stick gesture. +0: Arming/disarming triggers on switch transition. 1: Arming/disarming triggers when holding the momentary button down for COM_RC_ARM_HYST like the stick gesture. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -15911,17 +14337,15 @@ Arm switch is a momentary button. ### COM_ARM_WO_GPS (`INT32`) {#COM_ARM_WO_GPS} -Arming without GNSS configuration. +GPS preflight check. -Configures whether arming is allowed without GNSS, for modes that require a global position -(specifically, in those modes when a check defined by EKF2_GPS_CHECK fails). -The settings deny arming and warn, allow arming and warn, or silently allow arming. +Measures taken when a check defined by EKF2_GPS_CHECK is failing. **Values:** - `0`: Deny arming -- `1`: Allow arming (with warning) -- `2`: Allow arming (no warning) +- `1`: Warning only +- `2`: Disabled | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15931,8 +14355,7 @@ The settings deny arming and warn, allow arming and warn, or silently allow armi Maximum allowed CPU load to still arm. -The check fails if the CPU load is above this threshold for 2s. -A negative value disables the check. +The check fails if the CPU load is above this threshold for 2s. A negative value disables the check. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15942,9 +14365,7 @@ A negative value disables the check. Time-out for auto disarm after landing. -A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be -automatically disarmed in case a landing situation has been detected during this period. -A zero or negative value means that automatic disarming triggered by landing detection is disabled. +A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -15954,10 +14375,7 @@ A zero or negative value means that automatic disarming triggered by landing det Allow disarming via switch/stick/button on multicopters in manual thrust modes. -0: Disallow disarming when not landed -1: Allow disarming in multicopter flight in modes where -the thrust is directly controlled by thr throttle stick -e.g. Stabilized, Acro +0: Disallow disarming when not landed 1: Allow disarming in multicopter flight in modes where the thrust is directly controlled by thr throttle stick e.g. Stabilized, Acro | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -15967,10 +14385,7 @@ e.g. Stabilized, Acro Time-out for auto disarm if not taking off. -A non-zero, positive value specifies the time in seconds, within which the -vehicle is expected to take off after arming. In case the vehicle didn't takeoff -within the timeout it disarms again. -A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. +A non-zero, positive value specifies the time in seconds, within which the vehicle is expected to take off after arming. In case the vehicle didn't takeoff within the timeout it disarms again. A negative value disables autmoatic disarming triggered by a pre-takeoff timeout. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16006,11 +14421,7 @@ After this amount of seconds without datalink, the GCS connection lost mode trig Delay between failsafe condition triggered and failsafe reaction. -Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode -for the user to realize. -During that time the user can switch modes, but cannot take over control via the stick override feature (see COM_RC_OVERRIDE). -Afterwards the configured failsafe action is triggered and the user may use stick override. -A zero value disables the delay. +Before entering failsafe (RTL, Land, Hold), wait COM_FAIL_ACT_T seconds in Hold mode for the user to realize. During that time the user cannot take over control via the stick override feature (see COM_RC_OVERRIDE). Afterwards the configured failsafe action is triggered and the user may use stick override. A zero value disables the delay and the user cannot take over via stick movements (switching modes is still allowed). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16020,9 +14431,7 @@ A zero value disables the delay. Next flight UUID. -This number is incremented automatically after every flight on -disarming in order to remember the next flight UUID. -The first flight is 0. +This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16032,8 +14441,7 @@ The first flight is 0. Mode slot 1. -If the main switch channel is in this range the -selected flight mode will be applied. +If the main switch channel is in this range the selected flight mode will be applied. **Values:** @@ -16052,7 +14460,6 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land -- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16070,8 +14477,7 @@ selected flight mode will be applied. Mode slot 2. -If the main switch channel is in this range the -selected flight mode will be applied. +If the main switch channel is in this range the selected flight mode will be applied. **Values:** @@ -16090,7 +14496,6 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land -- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16108,8 +14513,7 @@ selected flight mode will be applied. Mode slot 3. -If the main switch channel is in this range the -selected flight mode will be applied. +If the main switch channel is in this range the selected flight mode will be applied. **Values:** @@ -16128,7 +14532,6 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land -- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16146,8 +14549,7 @@ selected flight mode will be applied. Mode slot 4. -If the main switch channel is in this range the -selected flight mode will be applied. +If the main switch channel is in this range the selected flight mode will be applied. **Values:** @@ -16166,7 +14568,6 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land -- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16184,8 +14585,7 @@ selected flight mode will be applied. Mode slot 5. -If the main switch channel is in this range the -selected flight mode will be applied. +If the main switch channel is in this range the selected flight mode will be applied. **Values:** @@ -16204,7 +14604,6 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land -- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16222,8 +14621,7 @@ selected flight mode will be applied. Mode slot 6. -If the main switch channel is in this range the -selected flight mode will be applied. +If the main switch channel is in this range the selected flight mode will be applied. **Values:** @@ -16242,7 +14640,6 @@ selected flight mode will be applied. - `11`: Land - `12`: Follow Me - `13`: Precision Land -- `16`: Altitude Cruise - `100`: External Mode 1 - `101`: External Mode 2 - `102`: External Mode 3 @@ -16260,8 +14657,7 @@ selected flight mode will be applied. Remaining flight time low failsafe. -Action the system takes when the remaining flight time is below -the estimated time it takes to reach the RTL destination. +Action the system takes when the remaining flight time is below the estimated time it takes to reach the RTL destination. **Values:** @@ -16271,15 +14667,13 @@ the estimated time it takes to reach the RTL destination. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | 1 | 0 | +|   | | | 1 | 3 | ### COM_FLT_PROFILE (`INT32`) {#COM_FLT_PROFILE} User Flight Profile. -Describes the intended use of the vehicle. -Can be used by ground control software or log post processing. -This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params). +Describes the intended use of the vehicle. Can be used by ground control software or log post processing. This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params). **Values:** @@ -16296,13 +14690,7 @@ This param does not influence the behavior within the firmware. This means for e Maximum allowed flight time. -The vehicle aborts the current operation and returns to launch when -the time since takeoff is above this value. It is not possible to resume the -mission or switch to any auto mode other than RTL or Land. Taking over in any manual -mode is still possible. -Starting from 90% of the maximum flight time, a warning message will be sent -every 1 minute with the remaining time until automatic RTL. -Set to -1 to disable. +The vehicle aborts the current operation and returns to launch when the time since takeoff is above this value. It is not possible to resume the mission or switch to any auto mode other than RTL or Land. Taking over in any manual mode is still possible. Starting from 90% of the maximum flight time, a warning message will be sent every 1 minute with the remaining time until automatic RTL. Set to -1 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16332,8 +14720,7 @@ After this amount of seconds without datalink the data link lost mode triggers High Latency Datalink regain time threshold. -After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' -flag is set back to false +After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss' flag is set back to false | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16343,10 +14730,7 @@ flag is set back to false Home position enabled. -Set home position automatically if possible. -During missions, the latitude/longitude of the home position is locked and will not reset during intermediate landings. -It will only update once the mission is complete or landed outside of a mission. -However, the altitude is still being adjusted to correct for GNSS vertical drift in the first 2 minutes after takeoff. +Set home position automatically if possible. During missions, the home position is locked and will not reset during intermediate landings. It will only update once the mission is complete or landed outside of a mission. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -16356,9 +14740,7 @@ However, the altitude is still being adjusted to correct for GNSS vertical drift Allows setting the home position after takeoff. -If set to true, the autopilot is allowed to set its home position after takeoff -The true home position is back-computed if a local position is estimate if available. -If no local position is available, home is set to the current position. +If set to true, the autopilot is allowed to set its home position after takeoff The true home position is back-computed if a local position is estimate if available. If no local position is available, home is set to the current position. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -16368,8 +14750,7 @@ If no local position is available, home is set to the current position. Imbalanced propeller failsafe mode. -Action the system takes when an imbalanced propeller is detected by the failure detector. -See also FD_IMB_PROP_THR to set the failure threshold. +Action the system takes when an imbalanced propeller is detected by the failure detector. See also FD_IMB_PROP_THR to set the failure threshold. **Values:** @@ -16386,8 +14767,6 @@ See also FD_IMB_PROP_THR to set the failure threshold. Timeout value for disarming when kill switch is engaged. -Use RC_MAP_KILL_SW to map a kill switch. - | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.0 | 30.0 | 0.1 | 5.0 | s | @@ -16396,10 +14775,7 @@ Use RC_MAP_KILL_SW to map a kill switch. Timeout for detecting a failure after takeoff. -A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle -if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. -The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). -A zero or negative value means that the check is disabled. +A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to disarm the vehicle if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW). A zero or negative value means that the check is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16409,8 +14785,7 @@ A zero or negative value means that the check is disabled. Battery failsafe mode. -Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR -for definition of battery states. +Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR for definition of battery states. **Values:** @@ -16426,9 +14801,7 @@ for definition of battery states. External mode identifier 0. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16438,9 +14811,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 1. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16450,9 +14821,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 2. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16462,9 +14831,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 3. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16474,9 +14841,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 4. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16486,9 +14851,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 5. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16498,9 +14861,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 6. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16510,9 +14871,7 @@ which is required when mapping an external mode to an RC switch. External mode identifier 7. -This parameter is automatically set to identify external modes. It ensures that modes -get assigned to the same index independent from their startup order, -which is required when mapping an external mode to an RC switch. +This parameter is automatically set to identify external modes. It ensures that modes get assigned to the same index independent from their startup order, which is required when mapping an external mode to an RC switch. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16532,8 +14891,7 @@ By default disabled for safety reasons Enable Actuator Testing. -If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that -allows spinning the motors and moving the servos for testing purposes. +If set, enables the actuator test interface via MAVLink (ACTUATOR_TEST), that allows spinning the motors and moving the servos for testing purposes. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -16551,8 +14909,7 @@ Time-out to wait when onboard computer connection is lost before warning about l Set offboard loss failsafe mode. -The offboard loss failsafe will only be entered after a timeout, -set by COM_OF_LOSS_T in seconds. +The offboard loss failsafe will only be entered after a timeout, set by COM_OF_LOSS_T in seconds. **Values:** @@ -16587,16 +14944,26 @@ Expect and require a healthy MAVLink parachute system. | ------ | -------- | -------- | --------- | ------------ | ---- | |   | | | | Disabled (0) | +### COM_POSCTL_NAVL (`INT32`) {#COM_POSCTL_NAVL} + +Position mode navigation loss response. + +This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode. + +**Values:** + +- `0`: Altitude mode +- `1`: Land mode (descend) + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + ### COM_POS_FS_EPH (`FLOAT`) {#COM_POS_FS_EPH} Horizontal position error threshold for hovering systems. -This is the horizontal position error (EPH) threshold that will trigger a failsafe. -If the previous position error was below this threshold, there is an additional -factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). -Only used for multicopters and VTOLs in hover mode. -Independent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT). -Set to -1 to disable. +This is the horizontal position error (EPH) threshold that will trigger a failsafe. If the previous position error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). Only used for multicopters and VTOLs in hover mode. Independent from estimator positioning data timeout threshold (see EKF2_NOAID_TOUT). Set to -1 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16606,10 +14973,7 @@ Set to -1 to disable. Low position accuracy action. -Action the system takes when the estimated position has an accuracy below the specified threshold. -See COM_POS_LOW_EPH to set the failsafe threshold. -The failsafe action is only executed if the vehicle is in auto mission or auto loiter mode, -otherwise it is only a warning. +Action the system takes when the estimated position has an accuracy below the specified threshold. See COM_POS_LOW_EPH to set the failsafe threshold. The failsafe action is only executed if the vehicle is in auto mission or auto loiter mode, otherwise it is only a warning. **Values:** @@ -16628,10 +14992,7 @@ otherwise it is only a warning. Low position accuracy failsafe threshold. -This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold. -Local position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT), -and a high failsafe threshold (COM_POS_FS_EPH). -Set to -1 to disable. +This triggers the action specified in COM_POS_LOW_ACT if the estimated position accuracy is below this threshold. Local position has to be still declared valid, which requires some kind of velocity aiding or large dead-reckoning time (EKF2_NOAID_TOUT), and a high failsafe threshold (COM_POS_FS_EPH). Set to -1 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16641,8 +15002,7 @@ Set to -1 to disable. Required number of redundant power modules. -This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. -Note: CBRK_SUPPLY_CHK disables all power checks including this one. +This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16652,8 +15012,7 @@ Note: CBRK_SUPPLY_CHK disables all power checks including this one. Condition to enter prearmed mode. -Condition to enter the prearmed state, an intermediate state between disarmed and armed -in which non-throttling actuators are active. +Condition to enter the prearmed state, an intermediate state between disarmed and armed in which non-throttling actuators are active. **Values:** @@ -16684,8 +15043,7 @@ Set action after a quadchute. Maximum allowed RAM usage to pass checks. -The check fails if the RAM usage is above this threshold. -A negative value disables the check. +The check fails if the RAM usage is above this threshold. A negative value disables the check. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16693,63 +15051,53 @@ A negative value disables the check. ### COM_RCL_EXCEPT (`INT32`) {#COM_RCL_EXCEPT} -Manual control loss exceptions. +RC loss exceptions. -Specify modes where manual control loss is ignored and no failsafe is triggered. -External modes requiring stick input will still failsafe. +Specify modes in which RC loss is ignored and the failsafe action not triggered. **Bitmask:** - `0`: Mission - `1`: Hold - `2`: Offboard -- `3`: External Mode -- `4`: Altitude Cruise | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 31 | | 0 | +|   | 0 | 7 | | 0 | + +### COM_RC_ARM_HYST (`INT32`) {#COM_RC_ARM_HYST} + +RC input arm/disarm command duration. + +The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 100 | 1500 | | 1000 | ms | ### COM_RC_IN_MODE (`INT32`) {#COM_RC_IN_MODE} -Manual control input source configuration. +RC control input mode. -Selects stick input selection behavior: -either a traditional remote control receiver (RC) or a MAVLink joystick (MANUAL_CONTROL message) -Priority sources are immediately switched to whenever they get valid. -0 RC only. Requires valid RC calibration. -1 MAVLink only. RC and related checks are disabled. -2 Switches only if current source becomes invalid. -3 Locks to the first valid source until reboot. -4 Ignores all sources. -5 RC priority, then MAVLink (lower instance before higher) -6 MAVLink priority (lower instance before higher), then RC -7 RC priority, then MAVLink (higher instance before lower) -8 MAVLink priority (higher instance before lower), then RC +A value of 0 enables RC transmitter control (only). A valid RC transmitter calibration is required. A value of 1 allows joystick control only. RC input handling and the associated checks are disabled. A value of 2 allows either RC Transmitter or Joystick input. The first valid input is used, will fallback to other sources if the input stream becomes invalid. A value of 3 allows either input from RC or joystick. The first available source is selected and used until reboot. A value of 4 ignores any stick input. **Values:** -- `0`: RC only -- `1`: MAVLink only -- `2`: RC or MAVLink with fallback -- `3`: RC or MAVLink keep first -- `4`: Disable manual control -- `5`: Prio: RC > MAVL 1 > MAVL 2 -- `6`: Prio: MAVL 1 > MAVL 2 > RC -- `7`: Prio: RC > MAVL 2 > MAVL 1 -- `8`: Prio: MAVL 2 > MAVL 1 > RC +- `0`: RC Transmitter only +- `1`: Joystick only +- `2`: RC and Joystick with fallback +- `3`: RC or Joystick keep first +- `4`: Stick input disabled | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 8 | | 3 | +|   | 0 | 4 | | 3 | ### COM_RC_LOSS_T (`FLOAT`) {#COM_RC_LOSS_T} Manual control loss timeout. -The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. -This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers. -Ensure the value is not set lower than the update interval of the RC or Joystick. +The time in seconds without a new setpoint from RC or Joystick, after which the connection is considered lost. This must be kept short as the vehicle will use the last supplied setpoint until the timeout triggers. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16757,12 +15105,9 @@ Ensure the value is not set lower than the update interval of the RC or Joystick ### COM_RC_OVERRIDE (`INT32`) {#COM_RC_OVERRIDE} -Enable manual control stick override. +Enable RC stick override of auto and/or offboard modes. -When enabled, moving the sticks more than COM_RC_STICK_OV -immediately gives control back to the pilot by switching to Position mode and -if position is unavailable Altitude mode. -Note: Only has an effect on multicopters, and VTOLs in multicopter mode. +When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV immediately gives control back to the pilot by switching to Position mode and if position is unavailable Altitude mode. Note: Only has an effect on multicopters, and VTOLs in multicopter mode. **Bitmask:** @@ -16775,10 +15120,9 @@ Note: Only has an effect on multicopters, and VTOLs in multicopter mode. ### COM_RC_STICK_OV (`FLOAT`) {#COM_RC_STICK_OV} -Stick override threshold. +RC stick override threshold. -If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold -the autopilot the pilot takes over control. +If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold the autopilot the pilot takes over control. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16788,12 +15132,7 @@ the autopilot the pilot takes over control. Enforced delay between arming and further navigation. -The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. -Goal: - -- Motors and propellers spool up to idle speed before getting commanded to spin faster -- Timeout for ESCs and smart batteries to successfulyy do failure checks - e.g. for stuck rotors before the vehicle is off the ground +The minimal time from arming the motors until moving the vehicle is possible is COM_SPOOLUP_TIME seconds. Goal: - Motors and propellers spool up to idle speed before getting commanded to spin faster - Timeout for ESCs and smart batteries to successfulyy do failure checks e.g. for stuck rotors before the vehicle is off the ground | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16828,10 +15167,7 @@ Allows to start the vehicle by throwing it into the air. Minimum speed for the throw start. -When the throw launch is enabled, the drone will only allow motors to spin after this speed -is exceeded before detecting the freefall. This is a safety feature to ensure the drone does -not turn on after accidental drop or a rapid movement before the throw. -Set to 0 to disable. +When the throw launch is enabled, the drone will only allow motors to spin after this speed is exceeded before detecting the freefall. This is a safety feature to ensure the drone does not turn on after accidental drop or a rapid movement before the throw. Set to 0 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16841,10 +15177,7 @@ Set to 0 to disable. Horizontal velocity error threshold. -This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. -The default is appropriate for a multicopter. Can be increased for a fixed-wing. -If the previous velocity error was below this threshold, there is an additional -factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). +This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing. If the previous velocity error was below this threshold, there is an additional factor of 2.5 applied (threshold for invalidation 2.5 times the one for validation). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16854,8 +15187,7 @@ factor of 2.5 applied (threshold for invalidation 2.5 times the one for validati High wind speed failsafe threshold. -Wind speed threshold above which an automatic failsafe action is triggered. -Failsafe action can be specified with COM_WIND_MAX_ACT. +Wind speed threshold above which an automatic failsafe action is triggered. Failsafe action can be specified with COM_WIND_MAX_ACT. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16865,11 +15197,7 @@ Failsafe action can be specified with COM_WIND_MAX_ACT. High wind failsafe mode. -Action the system takes when a wind speed above the specified threshold is detected. -See COM_WIND_MAX to set the failsafe threshold. -If enabled, it is not possible to resume the mission or switch to any auto mode other than -RTL or Land if this threshold is exceeded. Taking over in any manual -mode is still possible. +Action the system takes when a wind speed above the specified threshold is detected. See COM_WIND_MAX to set the failsafe threshold. If enabled, it is not possible to resume the mission or switch to any auto mode other than RTL or Land if this threshold is exceeded. Taking over in any manual mode is still possible. **Values:** @@ -16888,9 +15216,7 @@ mode is still possible. Wind speed warning threshold. -A warning is triggered if the currently estimated wind speed is above this value. -Warning is sent periodically (every 1 minute). -Set to -1 to disable. +A warning is triggered if the currently estimated wind speed is above this value. Warning is sent periodically (every 1 minute). Set to -1 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -16900,9 +15226,7 @@ Set to -1 to disable. Set GCS connection loss failsafe mode. -The GCS connection loss failsafe will only be entered after a timeout, -set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected -action will be executed. +The GCS connection loss failsafe will only be entered after a timeout, set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected action will be executed. **Values:** @@ -16919,10 +15243,9 @@ action will be executed. ### NAV_RCL_ACT (`INT32`) {#NAV_RCL_ACT} -Set manual control loss failsafe mode. +Set RC loss failsafe mode. -The manual control loss failsafe will only be entered after a timeout, -set by COM_RC_LOSS_T in seconds. +The RC loss failsafe will only be entered after a timeout, set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled by setting the COM_RC_IN_MODE param it will not be triggered. **Values:** @@ -16950,8 +15273,7 @@ UAVCAN/CAN v1 bus bitrate. Cyphal. -0 - Cyphal disabled. -1 - Enables Cyphal +0 - Cyphal disabled. 1 - Enables Cyphal | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -16961,7 +15283,7 @@ Cyphal. Cyphal Node ID. -Read the specs at https://opencyphal.org/ to learn more about Node ID. +Read the specs at http://uavcan.org to learn more about Node ID. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -17149,8 +15471,7 @@ sensor_gps uORB over Cyphal publication port ID. DSHOT 3D deadband high. -When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. -This value is with respect to the mixer_module range (0-1999), not the DSHOT values. +When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. This value is with respect to the mixer_module range (0-1999), not the DSHOT values. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -17160,8 +15481,7 @@ This value is with respect to the mixer_module range (0-1999), not the DSHOT val DSHOT 3D deadband low. -When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. -This value is with respect to the mixer_module range (0-1999), not the DSHOT values. +When the actuator_output is between DSHOT_3D_DEAD_L and DSHOT_3D_DEAD_H, motor will not spin. This value is with respect to the mixer_module range (0-1999), not the DSHOT values. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -17171,11 +15491,7 @@ This value is with respect to the mixer_module range (0-1999), not the DSHOT val Allows for 3d mode when using DShot and suitable mixer. -WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0. -This splits the throttle ranges in two. -Direction 1) 48 is the slowest, 1047 is the fastest. -Direction 2) 1049 is the slowest, 2047 is the fastest. -When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. +WARNING: ESC must be configured for 3D mode, and DSHOT_MIN set to 0. This splits the throttle ranges in two. Direction 1) 48 is the slowest, 1047 is the fastest. Direction 2) 1049 is the slowest, 2047 is the fastest. When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -17185,9 +15501,7 @@ When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent. Enable bidirectional DShot. -This parameter enables bidirectional DShot which provides RPM feedback. -Note that this requires ESCs that support bidirectional DSHot, e.g. BlHeli32. -This is not the same as DShot telemetry which requires an additional serial connection. +This parameter enables bidirectional DShot which provides RPM feedback. Note that this requires ESCs that support bidirectional DSHot, e.g. BlHeli32. This is not the same as DShot telemetry which requires an additional serial connection. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -17197,13 +15511,11 @@ This is not the same as DShot telemetry which requires an additional serial conn Minimum DShot Motor Output. -Minimum Output Value for DShot in percent. The value depends on the ESC. Make -sure to set this high enough so that the motors are always spinning while -armed. +Minimum Output Value for DShot in percent. The value depends on the ESC. Make sure to set this high enough so that the motors are always spinning while armed. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.055 | norm | +|   | 0 | 1 | 0.01 | 0.055 | % | ### DSHOT_TEL_CFG (`INT32`) {#DSHOT_TEL_CFG} @@ -17234,10 +15546,7 @@ Configure on which serial port to run DShot Driver. Number of magnetic poles of the motors. -Specify the number of magnetic poles of the motors. -It is required to compute the RPM value from the eRPM returned with the ESC telemetry. -Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). -Typical motors for 5 inch props have 14 poles. +Specify the number of magnetic poles of the motors. It is required to compute the RPM value from the eRPM returned with the ESC telemetry. Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). Typical motors for 5 inch props have 14 poles. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -17342,21 +15651,6 @@ Sets the number of standard deviations used by the innovation consistency test. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 1.0 | | | 3.0 | SD | -### EKF2_AGP_MODE (`INT32`) {#EKF2_AGP_MODE} - -Fusion reset mode. - -Automatic: reset on fusion timeout if no other source of position is available Dead-reckoning: reset on fusion timeout if no source of velocity is available - -**Values:** - -- `0`: Automatic -- `1`: Dead-reckoning - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - ### EKF2_AGP_NOISE (`FLOAT`) {#EKF2_AGP_NOISE} Measurement noise for aux global position measurements. @@ -17544,16 +15838,6 @@ EKF2 enable. | ------ | -------- | -------- | --------- | ----------- | ---- | |   | | | | Enabled (1) | -### EKF2_ENGINE_WRM (`INT32`) {#EKF2_ENGINE_WRM} - -Enable constant position fusion during engine warmup. - -When enabled, constant position fusion is enabled when the vehicle is landed and armed. This is intended for IC engine warmup (e.g., fuel engines on catapult) to allow mode transitions to auto/takeoff despite vibrations from running engines. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | - ### EKF2_EVA_NOISE (`FLOAT`) {#EKF2_EVA_NOISE} Measurement noise for vision angle measurements. @@ -17740,12 +16024,10 @@ Each threshold value is defined by the parameter indicated next to the check. Dr - `7`: Horizontal speed offset (EKF2_REQ_HDRIFT) - `8`: Vertical speed offset (EKF2_REQ_VDRIFT) - `9`: Spoofing -- `10`: GPS fix type (EKF2_REQ_FIX) -- `11`: Jamming | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 4095 | | 2047 | +|   | 0 | 1023 | | 1023 | ### EKF2_GPS_CTRL (`INT32`) {#EKF2_GPS_CTRL} @@ -17766,34 +16048,17 @@ Set bits in the following positions to enable: 0 : Longitude and latitude fusion ### EKF2_GPS_DELAY (`FLOAT`) {#EKF2_GPS_DELAY} -GPS measurement delay relative to IMU measurement. - -GPS measurement delay relative to IMU measurement if PPS time correction is not available/enabled (PPS_CAP_ENABLE). +GPS measurement delay relative to IMU measurements. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 300 | | 110 | ms | -### EKF2_GPS_MODE (`INT32`) {#EKF2_GPS_MODE} - -Fusion reset mode. - -Automatic: reset on fusion timeout if no other source of position is available. Dead-reckoning: reset on fusion timeout if no source of velocity is available. - -**Values:** - -- `0`: Automatic -- `1`: Dead-reckoning - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - ### EKF2_GPS_POS_X (`FLOAT`) {#EKF2_GPS_POS_X} X position of GPS antenna in body frame. -Forward (roll) axis with origin relative to vehicle centre of gravity +Forward axis with origin relative to vehicle centre of gravity | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -17803,7 +16068,7 @@ Forward (roll) axis with origin relative to vehicle centre of gravity Y position of GPS antenna in body frame. -Right (pitch) axis with origin relative to vehicle centre of gravity +Forward axis with origin relative to vehicle centre of gravity | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -17813,7 +16078,7 @@ Right (pitch) axis with origin relative to vehicle centre of gravity Z position of GPS antenna in body frame. -Down (yaw) axis with origin relative to vehicle centre of gravity +Forward axis with origin relative to vehicle centre of gravity | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -18125,7 +16390,7 @@ If the vehicle is on ground, is not moving as determined by the motion test and | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | | | 0.01 | m | +|   | 0.01 | | | 0.1 | m | ### EKF2_MULTI_IMU (`INT32`) {#EKF2_MULTI_IMU} @@ -18356,26 +16621,6 @@ Required EPV to use GPS. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 2 | 100 | | 5.0 | m | -### EKF2_REQ_FIX (`INT32`) {#EKF2_REQ_FIX} - -Required GPS fix. - -Minimum GPS fix type required for GPS usage. - -**Values:** - -- `0`: No fix required -- `2`: 2D fix -- `3`: 3D fix -- `4`: RTCM code differential -- `5`: RTK float -- `6`: RTK fixed -- `8`: Extrapolated - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 3 | - ### EKF2_REQ_GPS_H (`FLOAT`) {#EKF2_REQ_GPS_H} Required GPS health time on startup. @@ -18436,6 +16681,16 @@ If the vehicle absolute altitude exceeds this value then the estimator will not | ------ | -------- | -------- | --------- | ------- | ---- | |   | 1.0 | 10.0 | | 5.0 | m | +### EKF2_RNG_A_IGATE (`FLOAT`) {#EKF2_RNG_A_IGATE} + +Gate size used for innovation consistency checks for range aid fusion. + +A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 5.0 | | 1.0 | SD | + ### EKF2_RNG_A_VMAX (`FLOAT`) {#EKF2_RNG_A_VMAX} Maximum horizontal velocity allowed for conditional range aid mode. @@ -18720,11 +16975,7 @@ Required esc hardware version. RC Loss Alarm. -Enable/disable event task for RC Loss. When enabled, an alarm tune will be -played via buzzer or ESCs, if supported. The alarm will sound after a disarm, -if the vehicle was previously armed and only if the vehicle had RC signal at -some point. Particularly useful for locating crashed drones without a GPS -sensor. +Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -18734,12 +16985,7 @@ sensor. Status Display. -Enable/disable event task for displaying the vehicle status using arm-mounted -LEDs. When enabled and if the vehicle supports it, LEDs will flash -indicating various vehicle status changes. Currently PX4 has not implemented -any specific status events. - -- +Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. - | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -18771,8 +17017,7 @@ Applies to both directions in all manual modes with attitude stabilization Maximum manually added yaw rate. -This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. -It is added to the yaw rate setpoint generated by the controller for turn coordination. +This is the maximally added yaw rate setpoint from the yaw stick in any attitude controlled flight mode. It is added to the yaw rate setpoint generated by the controller for turn coordination. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -18782,9 +17027,7 @@ It is added to the yaw rate setpoint generated by the controller for turn coordi Pitch setpoint offset (pitch at level flight). -An airframe specific offset of the pitch setpoint in degrees, the value is -added to the pitch setpoint and should correspond to the pitch at -typical cruise speed of the airframe. +An airframe specific offset of the pitch setpoint in degrees, the value is added to the pitch setpoint and should correspond to the pitch at typical cruise speed of the airframe. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -18810,8 +17053,7 @@ Maximum positive / up pitch rate setpoint. Attitude pitch time constant. -This defines the latency between a pitch step input and the achieved setpoint -(inverse to a P gain). Smaller systems may require smaller values. +This defines the latency between a pitch step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -18829,8 +17071,7 @@ Maximum roll rate setpoint. Attitude Roll Time Constant. -This defines the latency between a roll step input and the achieved setpoint -(inverse to a P gain). Smaller systems may require smaller values. +This defines the latency between a roll step input and the achieved setpoint (inverse to a P gain). Smaller systems may require smaller values. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -18848,8 +17089,7 @@ Wheel steering rate feed forward. Wheel steering rate integrator gain. -This gain defines how much control response will result out of a steady -state error. It trims any constant error. +This gain defines how much control response will result out of a steady state error. It trims any constant error. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -18867,8 +17107,7 @@ Wheel steering rate integrator limit. Wheel steering rate proportional gain. -This defines how much the wheel steering input will be commanded depending on the -current body angular rate error. +This defines how much the wheel steering input will be commanded depending on the current body angular rate error. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------- | @@ -18878,8 +17117,7 @@ current body angular rate error. Enable wheel steering controller. -Only enabled during automatic runway takeoff and landing. -In all manual modes the wheel is directly controlled with yaw stick. +Only enabled during automatic runway takeoff and landing. In all manual modes the wheel is directly controlled with yaw stick. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -18889,8 +17127,7 @@ In all manual modes the wheel is directly controlled with yaw stick. Maximum wheel steering rate. -This limits the maximum wheel steering rate the controller will output (in degrees per -second). +This limits the maximum wheel steering rate the controller will output (in degrees per second). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -18910,8 +17147,7 @@ Maximum yaw rate setpoint. Flaps setting during landing. -Sets a fraction of full flaps during landing. -Also applies to flaperons if enabled in the mixer/allocation. +Sets a fraction of full flaps during landing. Also applies to flaperons if enabled in the mixer/allocation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -18921,13 +17157,7 @@ Also applies to flaperons if enabled in the mixer/allocation. Bit mask to set the automatic landing abort conditions. -Terrain estimation: -bit 0: Abort if terrain is not found -bit 1: Abort if terrain times out (after a first successful measurement) -The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the -selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. -TODO: Extend automatic abort conditions -e.g. glide slope tracking error (horizontal and vertical) +Terrain estimation: bit 0: Abort if terrain is not found bit 1: Abort if terrain times out (after a first successful measurement) The last estimate is always used as ground, whether the last valid measurement or the land waypoint, depending on the selected abort criteria, until an abort condition is entered. If FW_LND_USETER == 0, these bits are ignored. TODO: Extend automatic abort conditions e.g. glide slope tracking error (horizontal and vertical) **Bitmask:** @@ -18942,8 +17172,7 @@ e.g. glide slope tracking error (horizontal and vertical) Landing airspeed. -The calibrated airspeed setpoint during landing. -If set <= 0, landing airspeed = FW_AIRSPD_MIN by default. +The calibrated airspeed setpoint during landing. If set <= 0, landing airspeed = FW_AIRSPD_MIN by default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -18953,20 +17182,17 @@ If set <= 0, landing airspeed = FW_AIRSPD_MIN by default. Maximum landing slope angle. -Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. -Set this value within the vehicle's performance limits. +Typically the desired landing slope angle when landing configuration (flaps, airspeed) is enabled. Set this value within the vehicle's performance limits. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1.0 | 45.0 | 0.5 | 5.0 | deg | +|   | 1.0 | 15.0 | 0.5 | 5.0 | deg | ### FW_LND_EARLYCFG (`INT32`) {#FW_LND_EARLYCFG} Early landing configuration deployment. -Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in -the loiter-down waypoint before the final approach. -Otherwise is enabled only in the final approach. +Allows to deploy the landing configuration (flaps, landing airspeed, etc.) already in the loiter-down waypoint before the final approach. Otherwise is enabled only in the final approach. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -19016,9 +17242,7 @@ TECS will attempt to control the aircraft to this sink rate via pitch angle (thr Landing flare time. -Multiplied by the descent rate to calculate a dynamic altitude at which -to trigger the flare. -NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME \* descent rate) is taken as the flare altitude +Multiplied by the descent rate to calculate a dynamic altitude at which to trigger the flare. NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME \* descent rate) is taken as the flare altitude | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19028,11 +17252,7 @@ NOTE: max(FW_LND_FLALT, FW_LND_FL_TIME \* descent rate) is taken as the flare al Landing touchdown nudging option. -Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant -Approach path nudging: shifts the touchdown point laterally along with the entire approach path -This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the -desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is -relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle). +Approach angle nudging: shifts the touchdown point laterally while keeping the approach entrance point constant Approach path nudging: shifts the touchdown point laterally along with the entire approach path This is useful for manually adjusting the landing point in real time when map or GNSS errors cause an offset from the desired landing vector. Nudging is done with yaw stick, constrained to FW_LND_TD_OFF (in meters) and the direction is relative to the vehicle heading (stick deflection to the right = land point moves to the right as seen by the vehicle). **Values:** @@ -19056,11 +17276,7 @@ Maximum lateral position offset for the touchdown point. Landing touchdown time (since flare start). -This is the time after the start of flaring that we expect the vehicle to touch the runway. -At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. -If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. -Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. -The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME). +This is the time after the start of flaring that we expect the vehicle to touch the runway. At this time, a 0.5s clamp down ramp will engage, constraining the pitch setpoint to RWTO_PSP. If enabled, ensure that RWTO_PSP is configured appropriately for full gear contact on ground roll. Set to -1.0 to disable touchdown clamping. E.g. it may not be desirable to clamp on belly landings. The touchdown time will be constrained to be greater than or equal to the flare time (FW_LND_FL_TIME). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19080,10 +17296,7 @@ The TECS altitude time constant (FW_T_ALT_TC) is multiplied by this value. Use terrain estimation during landing. -This is critical for detecting when to flare, and should be enabled if possible. -If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing -will be aborted, depending on the criteria set in FW_LND_ABORT. -If disabled, FW_LND_ABORT terrain based criteria are ignored. +This is critical for detecting when to flare, and should be enabled if possible. If enabled and no measurement is found within a given timeout, the landing waypoint altitude will be used OR the landing will be aborted, depending on the criteria set in FW_LND_ABORT. If disabled, FW_LND_ABORT terrain based criteria are ignored. **Values:** @@ -19109,8 +17322,7 @@ Spoiler landing setting. Flaps setting during take-off. -Sets a fraction of full flaps during take-off. -Also applies to flaperons if enabled in the mixer/allocation. +Sets a fraction of full flaps during take-off. Also applies to flaperons if enabled in the mixer/allocation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19140,8 +17352,7 @@ Launch is detected when acceleration in body forward direction is above FW_LAUN_ Fixed-wing launch detection. -Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. -Not compatible with runway takeoff. +Enables automatic launch detection based on measured acceleration. Use for hand- or catapult-launched vehicles. Not compatible with runway takeoff. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -19161,8 +17372,7 @@ Start the motor(s) this amount of seconds after launch is detected. Takeoff Airspeed. -The calibrated airspeed setpoint during the takeoff climbout. -If set <= 0, FW_AIRSPD_MIN will be set by default. +The calibrated airspeed setpoint during the takeoff climbout. If set <= 0, FW_AIRSPD_MIN will be set by default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19174,7 +17384,7 @@ Minimum pitch during takeoff. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -5.0 | 80.0 | 0.5 | 10.0 | deg | +|   | -5.0 | 30.0 | 0.5 | 10.0 | deg | ## FW General @@ -19182,13 +17392,11 @@ Minimum pitch during takeoff. GPS failure loiter time. -The time the system should do open loop loiter and wait for GPS recovery -before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. -Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. +The time the system should do open loop loiter and wait for GPS recovery before it starts descending. Set to 0 to disable. Roll angle is set to FW_GPSF_R. Does only apply for fixed-wing vehicles or VTOLs with NAV_FORCE_VT set to 0. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | | | 30 | s | +|   | 0 | 3600 | | 30 | s | ### FW_GPSF_R (`FLOAT`) {#FW_GPSF_R} @@ -19198,7 +17406,7 @@ Roll angle in GPS failure loiter mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 60.0 | 0.5 | 15.0 | deg | +|   | 0.0 | 30.0 | 0.5 | 15.0 | deg | ### FW_POS_STK_CONF (`INT32`) {#FW_POS_STK_CONF} @@ -19223,7 +17431,7 @@ Applies in any altitude controlled flight mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 80.0 | 0.5 | 30.0 | deg | +|   | 0.0 | 60.0 | 0.5 | 30.0 | deg | ### FW_P_LIM_MIN (`FLOAT`) {#FW_P_LIM_MIN} @@ -19243,7 +17451,7 @@ Applies in any altitude controlled flight mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 35.0 | 75.0 | 0.5 | 50.0 | deg | +|   | 35.0 | 65.0 | 0.5 | 50.0 | deg | ### FW_THR_IDLE (`FLOAT`) {#FW_THR_IDLE} @@ -19253,14 +17461,13 @@ This is the minimum throttle while on the ground ("landed") in auto modes. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1.0 | 0.01 | 0.0 | norm | +|   | 0.0 | 0.4 | 0.01 | 0.0 | norm | ### FW_THR_MAX (`FLOAT`) {#FW_THR_MAX} Throttle limit max. -Applies in any altitude controlled flight mode. -Should be set accordingly to achieve FW_T_CLMB_MAX. +Applies in any altitude controlled flight mode. Should be set accordingly to achieve FW_T_CLMB_MAX. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19270,9 +17477,7 @@ Should be set accordingly to achieve FW_T_CLMB_MAX. Throttle limit min. -Applies in any altitude controlled flight mode. -Usually set to 0 but can be increased to prevent the motor from stopping when -descending, which can increase achievable descent rates. +Applies in any altitude controlled flight mode. Usually set to 0 but can be increased to prevent the motor from stopping when descending, which can increase achievable descent rates. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19282,32 +17487,27 @@ descending, which can increase achievable descent rates. Default target climbrate. -In auto modes: default climb rate output by controller to achieve altitude setpoints. -In manual modes: maximum climb rate setpoint. +In auto modes: default climb rate output by controller to achieve altitude setpoints. In manual modes: maximum climb rate setpoint. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | | 0.01 | 3.0 | m/s | +|   | 0.5 | 15 | 0.01 | 3.0 | m/s | ### FW_T_SINK_R_SP (`FLOAT`) {#FW_T_SINK_R_SP} Default target sinkrate. -In auto modes: default sink rate output by controller to achieve altitude setpoints. -In manual modes: maximum sink rate setpoint. +In auto modes: default sink rate output by controller to achieve altitude setpoints. In manual modes: maximum sink rate setpoint. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | | 0.01 | 2.0 | m/s | +|   | 0.5 | 15 | 0.01 | 2.0 | m/s | ### FW_T_SPDWEIGHT (`FLOAT`) {#FW_T_SPDWEIGHT} Speed <--> Altitude weight. -Adjusts the amount of weighting that the pitch control -applies to speed vs height errors. -0 -> control height only -2 -> control speed only (gliders) +Adjusts the amount of weighting that the pitch control applies to speed vs height errors. 0 -> control height only 2 -> control speed only (gliders) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19317,8 +17517,7 @@ applies to speed vs height errors. Height (AGL) of the wings when the aircraft is on the ground. -This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer -to give a slight margin here (> 0m) +This is used to constrain a minimum altitude below which we keep wings level to avoid wing tip strike. It's safer to give a slight margin here (> 0m) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19340,8 +17539,7 @@ This is used for limiting the roll setpoint near the ground. (if multiple wings, Path navigation roll slew rate limit. -Maximum change in roll angle setpoint per second. -Applied in all Auto modes, plus manual Position & Altitude modes. +Maximum change in roll angle setpoint per second. Applied in all Auto modes, plus manual Position & Altitude modes. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -19353,8 +17551,7 @@ Applied in all Auto modes, plus manual Position & Altitude modes. Minimum groundspeed. -The controller will increase the commanded airspeed to maintain -this minimum groundspeed to the next waypoint. +The controller will increase the commanded airspeed to maintain this minimum groundspeed to the next waypoint. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19382,8 +17579,7 @@ Altitude error time constant. Fast descend: minimum altitude error. -Minimum altitude error needed to descend with max airspeed and minimal throttle. -A negative value disables fast descend. +Minimum altitude error needed to descend with max airspeed and minimal throttle. A negative value disables fast descend. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19401,8 +17597,7 @@ Height rate feed forward. Integrator gain pitch. -Increase it to trim out speed and height offsets faster, -with the downside of possible overshoots and oscillations. +Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19420,9 +17615,7 @@ Pitch damping gain. Roll -> Throttle feedforward. -Is used to compensate for the additional drag created by turning. -Increase this gain if the aircraft initially loses energy in turns -and reduce if the aircraft initially gains energy in turns. +Is used to compensate for the additional drag created by turning. Increase this gain if the aircraft initially loses energy in turns and reduce if the aircraft initially gains energy in turns. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19458,8 +17651,7 @@ For the airspeed filter in TECS. Process noise standard deviation for the airspeed rate. -This is defining the noise in the airspeed rate for the constant airspeed rate model -of the TECS airspeed filter. +This is defining the noise in the airspeed rate for the constant airspeed rate model of the TECS airspeed filter. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -19507,8 +17699,7 @@ This is the damping gain for the throttle demand loop. Integrator gain throttle. -Increase it to trim out speed and height offsets faster, -with the downside of possible overshoots and oscillations. +Increase it to trim out speed and height offsets faster, with the downside of possible overshoots and oscillations. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19518,11 +17709,7 @@ with the downside of possible overshoots and oscillations. Low-height threshold for tighter altitude tracking. -Height above ground threshold below which tighter altitude -tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly -(1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC -to FW_LND_THRTC_SC\*FW_T_ALT_TC. --1 to disable. +Height above ground threshold below which tighter altitude tracking gets enabled (see FW_LND_THRTC_SC). Below this height, TECS smoothly (1 sec / sec) transitions the altitude tracking time constant from FW_T_ALT_TC to FW_LND_THRTC_SC\*FW_T_ALT_TC. -1 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19532,9 +17719,7 @@ to FW_LND_THRTC_SC\*FW_T_ALT_TC. Maximum vertical acceleration. -This is the maximum vertical acceleration -either up or down that the controller will use to correct speed -or height errors. +This is the maximum vertical acceleration either up or down that the controller will use to correct speed or height errors. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -19544,9 +17729,7 @@ or height errors. Wind-based airspeed scaling factor. -Multiplying this factor with the current absolute wind estimate gives the airspeed offset -added to the minimum airspeed setpoint limit. This helps to make the -system more robust against disturbances (turbulence) in high wind. +Multiplying this factor with the current absolute wind estimate gives the airspeed offset added to the minimum airspeed setpoint limit. This helps to make the system more robust against disturbances (turbulence) in high wind. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19568,8 +17751,7 @@ Damping ratio of NPFG control law. Enable automatic lower bound on the NPFG period. -Avoids limit cycling from a too aggressively tuned period/damping combination. -If false, also disables upper bound NPFG_PERIOD_UB. +Avoids limit cycling from a too aggressively tuned period/damping combination. If false, also disables upper bound NPFG_PERIOD_UB. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -19589,8 +17771,7 @@ Period of NPFG control law. Period safety factor. -Multiplied by period for conservative minimum period bounding (when period lower -bounding is enabled). 1.0 bounds at marginal stability. +Multiplied by period for conservative minimum period bounding (when period lower bounding is enabled). 1.0 bounds at marginal stability. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19600,8 +17781,7 @@ bounding is enabled). 1.0 bounds at marginal stability. Roll time constant. -Time constant of roll controller command / response, modeled as first order delay. -Used to determine lower period bound. Setting zero disables automatic period bounding. +Time constant of roll controller command / response, modeled as first order delay. Used to determine lower period bound. Setting zero disables automatic period bounding. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19611,8 +17791,7 @@ Used to determine lower period bound. Setting zero disables automatic period bou NPFG switch distance multiplier. -Multiplied by the track error boundary to determine when the aircraft switches -to the next waypoint and/or path segment. Should be less than 1. +Multiplied by the track error boundary to determine when the aircraft switches to the next waypoint and/or path segment. Should be less than 1. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19654,13 +17833,7 @@ The maximal airspeed (calibrated airspeed) the user is able to command. Minimum Airspeed (CAS). -The minimal airspeed (calibrated airspeed) the user is able to command. -Further, if the airspeed falls below this value, the TECS controller will try to -increase airspeed more aggressively. -Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), -with some margin between the stall speed and minimum airspeed. -This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), -and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE). +The minimal airspeed (calibrated airspeed) the user is able to command. Further, if the airspeed falls below this value, the TECS controller will try to increase airspeed more aggressively. Has to be set according to the vehicle's stall speed (which should be set in FW_AIRSPD_STALL), with some margin between the stall speed and minimum airspeed. This value corresponds to the desired minimum speed with the default load factor (level flight, default weight), and is automatically adpated to the current load factor (calculated from roll setpoint and WEIGHT_GROSS/WEIGHT_BASE). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19670,9 +17843,7 @@ and is automatically adpated to the current load factor (calculated from roll se Stall Airspeed (CAS). -The stall airspeed (calibrated airspeed) of the vehicle. -It is used for airspeed sensor failure detection and for the control -surface scaling airspeed limits. +The stall airspeed (calibrated airspeed) of the vehicle. It is used for airspeed sensor failure detection and for the control surface scaling airspeed limits. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19682,9 +17853,7 @@ surface scaling airspeed limits. Trim (Cruise) Airspeed. -The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, -this is the default airspeed setpoint that the controller will try to achieve. -This value corresponds to the trim airspeed with the default load factor (level flight, default weight). +The trim CAS (calibrated airspeed) of the vehicle. If an airspeed controller is active, this is the default airspeed setpoint that the controller will try to achieve. This value corresponds to the trim airspeed with the default load factor (level flight, default weight). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19694,9 +17863,7 @@ This value corresponds to the trim airspeed with the default load factor (level Service ceiling. -Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of -0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX. -Set negative to disable. +Altitude in standard atmosphere at which the vehicle in normal configuration (WEIGHT_BASE) is still able to achieve a maximum climb rate of 0.5m/s at maximum throttle (FW_THR_MAX). Used to compensate for air density in FW_T_CLMB_MAX. Set negative to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19706,8 +17873,7 @@ Set negative to disable. Throttle at max airspeed. -Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX -Set to 0 to disable mapping of airspeed to trim throttle. +Required throttle (at sea level, standard atmosphere) for level flight at maximum airspeed FW_AIRSPD_MAX Set to 0 to disable mapping of airspeed to trim throttle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19717,8 +17883,7 @@ Set to 0 to disable mapping of airspeed to trim throttle. Throttle at min airspeed. -Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN -Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM. +Required throttle (at sea level, standard atmosphere) for level flight at minimum airspeed FW_AIRSPD_MIN Set to 0 to disable mapping of airspeed to trim throttle below FW_AIRSPD_TRIM. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19738,33 +17903,27 @@ Required throttle (at sea level, standard atmosphere) for level flight at FW_AIR Maximum climb rate. -This is the maximum calibrated climb rate that the aircraft can achieve with -the throttle set to FW_THR_MAX and the airspeed set to the -trim value. For electric aircraft make sure this number can be -achieved towards the end of flight when the battery voltage has reduced. +This is the maximum calibrated climb rate that the aircraft can achieve with the throttle set to FW_THR_MAX and the airspeed set to the trim value. For electric aircraft make sure this number can be achieved towards the end of flight when the battery voltage has reduced. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1.0 | | 0.5 | 5.0 | m/s | +|   | 1.0 | 15.0 | 0.5 | 5.0 | m/s | ### FW_T_SINK_MIN (`FLOAT`) {#FW_T_SINK_MIN} Minimum descent rate. -This is the minimum calibrated sink rate of the aircraft with the throttle -set to THR_MIN and flown at the same airspeed as used -to measure FW_T_CLMB_MAX. +This is the minimum calibrated sink rate of the aircraft with the throttle set to THR_MIN and flown at the same airspeed as used to measure FW_T_CLMB_MAX. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1.0 | | 0.5 | 2.0 | m/s | +|   | 1.0 | 5.0 | 0.5 | 2.0 | m/s | ### WEIGHT_BASE (`FLOAT`) {#WEIGHT_BASE} Vehicle base weight. -This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value -disables trim throttle and minimum airspeed compensation based on weight. +This is the weight of the vehicle at which it's performance limits were derived. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19774,9 +17933,7 @@ disables trim throttle and minimum airspeed compensation based on weight. Vehicle gross weight. -This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added -or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value -disables trim throttle and minimum airspeed compensation based on weight. +This is the actual weight of the vehicle at any time. This value will differ from WEIGHT_BASE in case weight was added or removed from the base weight. Examples are the addition of payloads or larger batteries. A zero or negative value disables trim throttle and minimum airspeed compensation based on weight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19796,10 +17953,7 @@ Acro body roll max rate setpoint. Enable yaw rate controller in Acro. -If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. -Otherwise the pilot commands directly the yaw actuator. -It is disabled by default because an active yaw rate controller will fight against the -natural turn coordination of the plane. +If this parameter is set to 1, the yaw rate controller is enabled in Fixed-wing Acro mode. Otherwise the pilot commands directly the yaw actuator. It is disabled by default because an active yaw rate controller will fight against the natural turn coordination of the plane. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -19825,11 +17979,7 @@ Acro body yaw max rate setpoint. Enable airspeed scaling. -This enables a logic that automatically adjusts the output of the rate controller to take -into account the real torque produced by an aerodynamic control surface given -the current deviation from the trim airspeed (FW_AIRSPD_TRIM). -Enable when using aerodynamic control surfaces (e.g.: plane) -Disable when using rotor wings (e.g.: autogyro) +This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -19839,8 +17989,7 @@ Disable when using rotor wings (e.g.: autogyro) Enable throttle scale by battery level. -This compensates for voltage drop of the battery over time by attempting to -normalize performance across the operating range of the battery. +This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -19906,30 +18055,11 @@ This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN. | ------ | -------- | -------- | --------- | ------- | ---- | |   | -0.5 | 0.5 | 0.01 | 0.0 | -### FW_GC_EN (`INT32`) {#FW_GC_EN} - -Enable rate gain compression. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | - -### FW_GC_GAIN_MIN (`FLOAT`) {#FW_GC_GAIN_MIN} - -Compression gain lower limit. - -The range of the compression gain is between this parameter and 1.0 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1.0 | 0.01 | 0.3 | - ### FW_MAN_P_SC (`FLOAT`) {#FW_MAN_P_SC} Manual pitch scale. -Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows -to adjust the throws of the control surfaces. +Scale factor applied to the desired pitch actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19939,8 +18069,7 @@ to adjust the throws of the control surfaces. Manual roll scale. -Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows -to adjust the throws of the control surfaces. +Scale factor applied to the desired roll actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -19950,8 +18079,7 @@ to adjust the throws of the control surfaces. Manual yaw scale. -Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows -to adjust the throws of the control surfaces. +Scale factor applied to the desired yaw actuator command in full manual mode. This parameter allows to adjust the throws of the control surfaces. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20005,9 +18133,7 @@ Pitch rate proportional gain. Roll control to yaw control feedforward gain. -This gain can be used to counteract the "adverse yaw" effect for fixed wings. -When the plane enters a roll it will tend to yaw the nose out of the turn. -This gain enables the use of a yaw actuator to counteract this effect. +This gain can be used to counteract the "adverse yaw" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator to counteract this effect. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20075,12 +18201,7 @@ Chose source for manual setting of spoilers in manual flight modes. Use airspeed for control. -If set to 1, the airspeed measurement data, if valid, is used in the following controllers: - -- Rate controller: output scaling -- Attitude controller: coordinated turn controller -- Position controller: airspeed setpoint tracking, takeoff logic -- VTOL: transition logic +If set to 1, the airspeed measurement data, if valid, is used in the following controllers: - Rate controller: output scaling - Attitude controller: coordinated turn controller - Position controller: airspeed setpoint tracking, takeoff logic - VTOL: transition logic | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -20134,9 +18255,7 @@ Yaw rate proportional gain. Enable Actuator Failure check. -If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle -level is being consumed. -Otherwise this indicates an motor failure. +If enabled, failure detector will verify that for motors, a minimum amount of ESC current per throttle level is being consumed. Otherwise this indicates an motor failure. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -20166,8 +18285,7 @@ Motor failure triggers only above this throttle value. Motor Failure Time Threshold. -Motor failure triggers only if the throttle threshold and the -current to throttle threshold are violated for this time. +Motor failure triggers only if the throttle threshold and the current to throttle threshold are violated for this time. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20177,8 +18295,7 @@ current to throttle threshold are violated for this time. Enable checks on ESCs that report their arming state. -If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. -Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. +If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -20188,8 +18305,7 @@ Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback i Enable PWM input on for engaging failsafe from an external automatic trigger system (ATS). -Enabled on either AUX5 or MAIN5 depending on board. -External ATS is required by ASTM F3322-18. +Enabled on either AUX5 or MAIN5 depending on board. External ATS is required by ASTM F3322-18. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -20209,12 +18325,7 @@ External ATS is required by ASTM F3322-18. FailureDetector Max Pitch. -Maximum pitch angle before FailureDetector triggers the attitude_failure flag. -The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), -which sets outputs to their failsafe values. -On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), -which disarms motors but does not set outputs to failsafe values. -Setting this parameter to 0 disables the check +Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20234,12 +18345,7 @@ Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as FailureDetector Max Roll. -Maximum roll angle before FailureDetector triggers the attitude_failure flag. -The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), -which sets outputs to their failsafe values. -On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), -which disarms motors but does not set outputs to failsafe values. -Setting this parameter to 0 disables the check +Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20259,9 +18365,7 @@ Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a Imbalanced propeller check threshold. -Value at which the imbalanced propeller metric (based on horizontal and -vertical acceleration variance) triggers a failure -Setting this value to 0 disables the feature. +Value at which the imbalanced propeller metric (based on horizontal and vertical acceleration variance) triggers a failure Setting this value to 0 disables the feature. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20287,7 +18391,7 @@ Yaw behaviour during orbit flight. - `1`: Hold Initial Heading - `2`: Uncontrolled - `3`: Hold Front Tangent to Circle -- `4`: Manually (yaw stick) Controlled +- `4`: RC Controlled | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20299,10 +18403,7 @@ Yaw behaviour during orbit flight. Altitude control mode. -Maintain altitude or track target's altitude. When maintaining the altitude, -the drone can crash into terrain when the target moves uphill. When tracking -the target's altitude, the follow altitude FLW_TGT_HT should be high enough -to prevent terrain collisions due to GPS inaccuracies of the target. +Maintain altitude or track target's altitude. When maintaining the altitude, the drone can crash into terrain when the target moves uphill. When tracking the target's altitude, the follow altitude FLW_TGT_HT should be high enough to prevent terrain collisions due to GPS inaccuracies of the target. **Values:** @@ -20328,11 +18429,7 @@ The distance in meters to follow the target at Follow Angle setting in degrees. -Angle to follow the target from. 0.0 Equals straight in front of the target's -course (direction of motion) and the angle increases in clockwise direction, -meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees -Note: When the user force sets the angle out of the min/max range, it will be -wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range. +Angle to follow the target from. 0.0 Equals straight in front of the target's course (direction of motion) and the angle increases in clockwise direction, meaning Right-side would be 90.0 degrees while Left-side is -90.0 degrees Note: When the user force sets the angle out of the min/max range, it will be wrapped (e.g. 480 -> 120) in the range to gracefully handle the out of range. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20352,8 +18449,7 @@ Following height above the target Maximum tangential velocity setting for generating the follow orbit trajectory. -This is the maximum tangential velocity the drone will circle around the target whenever -an orbit angle setpoint changes. Higher value means more aggressive follow behavior. +This is the maximum tangential velocity the drone will circle around the target whenever an orbit angle setpoint changes. Higher value means more aggressive follow behavior. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20400,17 +18496,7 @@ Configure on which serial port to run Main GPS. GNSS Systems for Primary GPS (integer bitmask). -This integer bitmask controls the set of GNSS systems used by the receiver. Check your -receiver's documentation on how many systems are supported to be used in parallel. -Currently this functionality is just implemented for u-blox receivers. -When no bits are set, the receiver's default configuration should be used. -Set bits true to enable: -0 : Use GPS (with QZSS) -1 : Use SBAS (multiple GPS augmentation systems) -2 : Use Galileo -3 : Use BeiDou -4 : Use GLONASS -5 : Use NAVIC +This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC **Bitmask:** @@ -20429,8 +18515,7 @@ Set bits true to enable: Protocol for Main GPS. -Select the GPS protocol over serial. -Auto-detection will probe all protocols, and thus is a bit slower. +Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. **Values:** @@ -20475,17 +18560,7 @@ Configure on which serial port to run Secondary GPS. GNSS Systems for Secondary GPS (integer bitmask). -This integer bitmask controls the set of GNSS systems used by the receiver. Check your -receiver's documentation on how many systems are supported to be used in parallel. -Currently this functionality is just implemented for u-blox receivers. -When no bits are set, the receiver's default configuration should be used. -Set bits true to enable: -0 : Use GPS (with QZSS) -1 : Use SBAS (multiple GPS augmentation systems) -2 : Use Galileo -3 : Use BeiDou -4 : Use GLONASS -5 : Use NAVIC +This integer bitmask controls the set of GNSS systems used by the receiver. Check your receiver's documentation on how many systems are supported to be used in parallel. Currently this functionality is just implemented for u-blox receivers. When no bits are set, the receiver's default configuration should be used. Set bits true to enable: 0 : Use GPS (with QZSS) 1 : Use SBAS (multiple GPS augmentation systems) 2 : Use Galileo 3 : Use BeiDou 4 : Use GLONASS 5 : Use NAVIC **Bitmask:** @@ -20504,8 +18579,7 @@ Set bits true to enable: Protocol for Secondary GPS. -Select the GPS protocol over serial. -Auto-detection will probe all protocols, and thus is a bit slower. +Select the GPS protocol over serial. Auto-detection will probe all protocols, and thus is a bit slower. **Values:** @@ -20521,28 +18595,11 @@ Auto-detection will probe all protocols, and thus is a bit slower. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 6 | | 1 | -### GPS_CFG_WIPE (`INT32`) {#GPS_CFG_WIPE} - -Wipes the flash config of UBX modules. - -Some UBX modules have a FLASH that allows to store persistent configuration that will be loaded on start. -PX4 does override all configuration parameters it needs in RAM, which takes precedence over the values in FLASH. -However, configuration parameters that are not overriden by PX4 can still cause unexpected problems during flight. -To avoid these kind of problems a clean config can be reached by wiping the FLASH on boot. -Note: Currently only supported on UBX. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - ### GPS_DUMP_COMM (`INT32`) {#GPS_DUMP_COMM} Log GPS communication data. -If this is set to 1, all GPS communication data will be published via uORB, -and written to the log file as gps_dump message. -If this is set to 2, the main GPS is configured to output RTCM data, -which is then logged as gps_dump and can be used for PPK. +If this is set to 1, all GPS communication data will be published via uORB, and written to the log file as gps_dump message. If this is set to 2, the main GPS is configured to output RTCM data, which is then logged as gps_dump and can be used for PPK. **Values:** @@ -20558,8 +18615,7 @@ which is then logged as gps_dump and can be used for PPK. Enable sat info (if available). -Enable publication of satellite info (ORB_ID(satellite_info)) if possible. -Not available on MTK. +Enable publication of satellite info (ORB_ID(satellite_info)) if possible. Not available on MTK. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -20569,9 +18625,7 @@ Not available on MTK. u-blox F9P UART2 Baudrate. -Select a baudrate for the F9P's UART2 port. -In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. -Set this to 57600 if you want to attach a telemetry radio on UART2. +Select a baudrate for the F9P's UART2 port. In GPS_UBX_MODE 1, 2, and 3, the F9P's UART2 port is configured to send/receive RTCM corrections. Set this to 57600 if you want to attach a telemetry radio on UART2. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -20598,8 +18652,7 @@ u-blox protocol configuration for interfaces. u-blox GPS dynamic platform model. -u-blox receivers support different dynamic platform models to adjust the navigation engine to -the expected application environment. +u-blox receivers support different dynamic platform models to adjust the navigation engine to the expected application environment. **Values:** @@ -20617,16 +18670,7 @@ the expected application environment. u-blox GPS Mode. -Select the u-blox configuration setup. Most setups will use the default, including RTK and -dual GPS without heading. -If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. -The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output -heading information, whereas the secondary will act as moving base. -Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the -F9P units are connected to each other. -Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. -RTK is still possible with this setup. -Mode 6 is intended for use with a ground control station (not necessarily an RTK correction base). +Select the u-blox configuration setup. Most setups will use the default, including RTK and dual GPS without heading. If rover has RTCM corrections from a static base (or other static correction source) coming in on UART2, then select Mode 5. The Heading mode requires 2 F9P devices to be attached. The main GPS will act as rover and output heading information, whereas the secondary will act as moving base. Modes 1 and 2 require each F9P UART1 to be connected to the Autopilot. In addition, UART2 on the F9P units are connected to each other. Modes 3 and 4 only require UART1 on each F9P connected to the Autopilot or Can Node. UART RX DMA is required. RTK is still possible with this setup. **Values:** @@ -20636,33 +18680,16 @@ Mode 6 is intended for use with a ground control station (not necessarily an RTK - `3`: Heading (Rover With Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - `4`: Moving Base (Moving Base UART1 Connected to Autopilot Or Can Node At 921600) - `5`: Rover with Static Base on UART2 (similar to Default, except coming in on UART2) -- `6`: Ground Control Station (UART2 outputs NMEA) | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 0 | 1 | | 0 | -### GPS_UBX_PPK (`INT32`) {#GPS_UBX_PPK} - -Enable MSM7 message output for PPK workflow. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - ### GPS_YAW_OFFSET (`FLOAT`) {#GPS_YAW_OFFSET} Heading/Yaw offset for dual antenna GPS. -Heading offset angle for dual antenna GPS setups that support heading estimation. -Set this to 0 if the antennas are parallel to the forward-facing direction -of the vehicle and the rover (or Unicore primary) antenna is in front. -The offset angle increases clockwise. -Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) -antenna is placed on the right side of the vehicle and the moving base -antenna is on the left side. -(Note: the Unicore primary antenna is the one connected on the right as seen -from the top). +Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover (or Unicore primary) antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover (or Unicore primary, or Septentrio Mosaic Aux) antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. (Note: the Unicore primary antenna is the one connected on the right as seen from the top). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -20684,8 +18711,7 @@ Enables the PPS capture module to refine the GPS time from pulses detected on a Geofence violation action. -Note: Setting this value to 4 enables flight termination, -which will kill the vehicle on violation of the fence. +Note: Setting this value to 4 enables flight termination, which will kill the vehicle on violation of the fence. **Values:** @@ -20704,8 +18730,7 @@ which will kill the vehicle on violation of the fence. Max horizontal distance from Home. -Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. -Disabled if 0. +Maximum horizontal distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20715,8 +18740,7 @@ Disabled if 0. Max vertical distance from Home. -Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. -Disabled if 0. +Maximum vertical distance in meters the vehicle can be from Home before triggering a geofence action. Disabled if 0. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20726,10 +18750,7 @@ Disabled if 0. [EXPERIMENTAL] Use Pre-emptive geofence triggering. -WARNING: This experimental feature may cause flyaways. Use at your own risk. -Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory -would result in a breach happening before the vehicle can make evasive maneuvers. -The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). +WARNING: This experimental feature may cause flyaways. Use at your own risk. Predict the motion of the vehicle and trigger the breach if it is determined that the current trajectory would result in a breach happening before the vehicle can make evasive maneuvers. The vehicle is then re-routed to a safe hold position (stop for multirotor, loiter for fixed wing). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -20739,9 +18760,7 @@ The vehicle is then re-routed to a safe hold position (stop for multirotor, loit Geofence source. -Select which position source should be used. Selecting GPS instead of global position makes sure that there is -no dependence on the position estimator -0 = global position, 1 = GPS +Select which position source should be used. Selecting GPS instead of global position makes sure that there is no dependence on the position estimator 0 = global position, 1 = GPS **Values:** @@ -20758,9 +18777,7 @@ no dependence on the position estimator Airframe selection. -Defines which mixer implementation to use. -Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. -'Custom' should only be used if noting else can be used. +Defines which mixer implementation to use. Some are generic, while others are specifically fit to a certain vehicle with a fixed set of actuators. 'Custom' should only be used if noting else can be used. **Values:** @@ -20789,8 +18806,7 @@ Some are generic, while others are specifically fit to a certain vehicle with a Motor failure handling mode. -This is used to specify how to handle motor failures -reported by failure detector. +This is used to specify how to handle motor failures reported by failure detector. **Values:** @@ -20805,8 +18821,7 @@ reported by failure detector. Collective pitch curve at position 0. -Defines the collective pitch at the interval position 0 for a given thrust setpoint. -Use negative values if the swash plate needs to move down to provide upwards thrust. +Defines the collective pitch at the interval position 0 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20816,8 +18831,7 @@ Use negative values if the swash plate needs to move down to provide upwards thr Collective pitch curve at position 1. -Defines the collective pitch at the interval position 1 for a given thrust setpoint. -Use negative values if the swash plate needs to move down to provide upwards thrust. +Defines the collective pitch at the interval position 1 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20827,8 +18841,7 @@ Use negative values if the swash plate needs to move down to provide upwards thr Collective pitch curve at position 2. -Defines the collective pitch at the interval position 2 for a given thrust setpoint. -Use negative values if the swash plate needs to move down to provide upwards thrust. +Defines the collective pitch at the interval position 2 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20838,8 +18851,7 @@ Use negative values if the swash plate needs to move down to provide upwards thr Collective pitch curve at position 3. -Defines the collective pitch at the interval position 3 for a given thrust setpoint. -Use negative values if the swash plate needs to move down to provide upwards thrust. +Defines the collective pitch at the interval position 3 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20849,8 +18861,7 @@ Use negative values if the swash plate needs to move down to provide upwards thr Collective pitch curve at position 4. -Defines the collective pitch at the interval position 4 for a given thrust setpoint. -Use negative values if the swash plate needs to move down to provide upwards thrust. +Defines the collective pitch at the interval position 4 for a given thrust setpoint. Use negative values if the swash plate needs to move down to provide upwards thrust. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20870,8 +18881,7 @@ Same definition as the proportional gain but for integral. Proportional gain for rpm control. -Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. -motor_command = throttle_curve + CA_HELI_RPM_P \* (rpm_setpoint - rpm_measurement) / 1000 +Ratio between rpm error devided by 1000 to how much normalized output gets added to correct for it. motor_command = throttle_curve + CA_HELI_RPM_P \* (rpm_setpoint - rpm_measurement) / 1000 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20941,10 +18951,7 @@ Defines the output throttle at the interval position 4. Main rotor turns counter-clockwise. -Default configuration is for a clockwise turning main rotor and -positive thrust of the tail rotor is expected to rotate the vehicle clockwise. -Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction -which is mostly the case when the main rotor turns counter-clockwise. +Default configuration is for a clockwise turning main rotor and positive thrust of the tail rotor is expected to rotate the vehicle clockwise. Set this parameter to true if the tail rotor provides thrust in counter-clockwise direction which is mostly the case when the main rotor turns counter-clockwise. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -20954,12 +18961,7 @@ which is mostly the case when the main rotor turns counter-clockwise. Offset for yaw compensation based on collective pitch. -This allows to specify which collective pitch command results in the least amount of rotor drag. -This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch -by aligning the lowest rotor drag with zero compensation. -For symmetric profile blades this is the command that results in exactly 0° collective blade angle. -For lift profile blades this is typically a command resulting in slightly negative collective blade angle. -tail_output += CA_HELI_YAW_CP_S \* abs(collective_pitch - CA_HELI_YAW_CP_O) +This allows to specify which collective pitch command results in the least amount of rotor drag. This is used to increase the accuracy of the yaw drag torque compensation based on collective pitch by aligning the lowest rotor drag with zero compensation. For symmetric profile blades this is the command that results in exactly 0° collective blade angle. For lift profile blades this is typically a command resulting in slightly negative collective blade angle. tail_output += CA_HELI_YAW_CP_S \* abs(collective_pitch - CA_HELI_YAW_CP_O) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20969,9 +18971,7 @@ tail_output += CA_HELI_YAW_CP_S \* abs(collective_pitch - CA_HELI_YAW_CP_O) Scale for yaw compensation based on collective pitch. -This allows to add a proportional factor of the collective pitch command to the yaw command. -A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. -tail_output += CA_HELI_YAW_CP_S \* abs(collective_pitch - CA_HELI_YAW_CP_O) +This allows to add a proportional factor of the collective pitch command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_CP_S \* abs(collective_pitch - CA_HELI_YAW_CP_O) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20981,9 +18981,7 @@ tail_output += CA_HELI_YAW_CP_S \* abs(collective_pitch - CA_HELI_YAW_CP_O) Scale for yaw compensation based on throttle. -This allows to add a proportional factor of the throttle command to the yaw command. -A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. -tail_output += CA_HELI_YAW_TH_S \* throttle +This allows to add a proportional factor of the throttle command to the yaw command. A negative value is needed when positive thrust of the tail rotor rotates the vehicle opposite to the main rotor turn direction. tail_output += CA_HELI_YAW_TH_S \* throttle | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -20993,9 +18991,7 @@ tail_output += CA_HELI_YAW_TH_S \* throttle Throw angle of swashplate servo at maximum commands for linearization. -Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy. -This requires a symmetric setup where the servo horn is exactly centered with a 0 command. -Setting to zero disables feature. +Used to linearize mechanical output of swashplate servos to avoid axis coupling and binding with 4 servo redundancy. This requires a symmetric setup where the servo horn is exactly centered with a 0 command. Setting to zero disables feature. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21005,8 +19001,7 @@ Setting to zero disables feature. Control allocation method. -Selects the algorithm and desaturation method. -If set to Automatic, the selection is based on the airframe (CA_AIRFRAME). +Selects the algorithm and desaturation method. If set to Automatic, the selection is based on the airframe (CA_AIRFRAME). **Values:** @@ -21022,9 +19017,7 @@ If set to Automatic, the selection is based on the airframe (CA_AIRFRAME). Motor 0 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21034,9 +19027,7 @@ Zero means that slew rate limiting is disabled. Motor 10 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21046,9 +19037,7 @@ Zero means that slew rate limiting is disabled. Motor 11 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21058,9 +19047,7 @@ Zero means that slew rate limiting is disabled. Motor 1 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21070,9 +19057,7 @@ Zero means that slew rate limiting is disabled. Motor 2 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21082,9 +19067,7 @@ Zero means that slew rate limiting is disabled. Motor 3 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21094,9 +19077,7 @@ Zero means that slew rate limiting is disabled. Motor 4 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21106,9 +19087,7 @@ Zero means that slew rate limiting is disabled. Motor 5 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21118,9 +19097,7 @@ Zero means that slew rate limiting is disabled. Motor 6 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21130,9 +19107,7 @@ Zero means that slew rate limiting is disabled. Motor 7 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21142,9 +19117,7 @@ Zero means that slew rate limiting is disabled. Motor 8 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21154,9 +19127,7 @@ Zero means that slew rate limiting is disabled. Motor 9 slew rate limit. -Forces the motor output signal to take at least the configured time (in seconds) -to traverse its full range (normally [0, 1], or if reversible [-1, 1]). -Zero means that slew rate limiting is disabled. +Forces the motor output signal to take at least the configured time (in seconds) to traverse its full range (normally [0, 1], or if reversible [-1, 1]). Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21196,9 +19167,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 0. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21208,9 +19177,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 0. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21292,9 +19259,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 10. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21304,9 +19269,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 10. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21388,9 +19351,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 11. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21400,9 +19361,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 11. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21484,9 +19443,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 1. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21496,9 +19453,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 1. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21580,9 +19535,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 2. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21592,9 +19545,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 2. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21676,9 +19627,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 3. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21688,9 +19637,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 3. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21772,9 +19719,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 4. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21784,9 +19729,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 4. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21868,9 +19811,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 5. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21880,9 +19821,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 5. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21964,9 +19903,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 6. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -21976,9 +19913,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 6. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22060,9 +19995,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 7. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22072,9 +20005,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 7. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22156,9 +20087,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 8. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22168,9 +20097,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 8. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22252,9 +20179,7 @@ Only the direction is considered (the vector is normalized). Thrust coefficient of rotor 9. -The thrust coefficient if defined as Thrust = CT \* u^2, -where u (with value between actuator minimum and maximum) -is the output signal sent to the motor controller. +The thrust coefficient if defined as Thrust = CT \* u^2, where u (with value between actuator minimum and maximum) is the output signal sent to the motor controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22264,9 +20189,7 @@ is the output signal sent to the motor controller. Moment coefficient of rotor 9. -The moment coefficient if defined as Torque = KM \* Thrust. -Use a positive value for a rotor with CCW rotation. -Use a negative value for a rotor with CW rotation. +The moment coefficient if defined as Torque = KM \* Thrust. Use a positive value for a rotor with CCW rotation. Use a negative value for a rotor with CW rotation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22461,9 +20384,7 @@ Number of swash plates servos. Servo 0 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22473,9 +20394,7 @@ Zero means that slew rate limiting is disabled. Servo 1 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22485,9 +20404,7 @@ Zero means that slew rate limiting is disabled. Servo 2 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22497,9 +20414,7 @@ Zero means that slew rate limiting is disabled. Servo 3 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22509,9 +20424,7 @@ Zero means that slew rate limiting is disabled. Servo 4 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22521,9 +20434,7 @@ Zero means that slew rate limiting is disabled. Servo 5 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22533,9 +20444,7 @@ Zero means that slew rate limiting is disabled. Servo 6 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22545,9 +20454,7 @@ Zero means that slew rate limiting is disabled. Servo 7 slew rate limit. -Forces the servo output signal to take at least the configured time (in seconds) -to traverse its full range [-100%, 100%]. -Zero means that slew rate limiting is disabled. +Forces the servo output signal to take at least the configured time (in seconds) to traverse its full range [-100%, 100%]. Zero means that slew rate limiting is disabled. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22574,8 +20481,6 @@ Control Surface 0 configuration as spoiler. Control Surface 0 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22656,8 +20561,6 @@ Control Surface 1 configuration as spoiler. Control Surface 1 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22738,8 +20641,6 @@ Control Surface 2 configuration as spoiler. Control Surface 2 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22820,8 +20721,6 @@ Control Surface 3 configuration as spoiler. Control Surface 3 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22902,8 +20801,6 @@ Control Surface 4 configuration as spoiler. Control Surface 4 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -22984,8 +20881,6 @@ Control Surface 5 configuration as spoiler. Control Surface 5 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23066,8 +20961,6 @@ Control Surface 6 configuration as spoiler. Control Surface 6 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23148,8 +21041,6 @@ Control Surface 7 configuration as spoiler. Control Surface 7 trim. Can be used to add an offset to the servo control. -NOTE: Do not use for PWM servos. Use the PWM CENTER parameters instead (e.g., PWM_MAIN_CENT, PWM_AUX_CENT) instead. -This parameter can only be set if all PWM Center parameters are set to default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23250,8 +21141,7 @@ Define if this servo is used for additional control. Tilt Servo 0 Tilt Angle at Maximum. -Defines the tilt angle when the servo is at the maximum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23261,8 +21151,7 @@ An angle of zero means upwards. Tilt Servo 0 Tilt Angle at Minimum. -Defines the tilt angle when the servo is at the minimum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23272,9 +21161,7 @@ An angle of zero means upwards. Tilt Servo 0 Tilt Direction. -Defines the direction the servo tilts towards when moving towards the maximum tilt angle. -For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', -the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. +Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. **Values:** @@ -23306,8 +21193,7 @@ Define if this servo is used for additional control. Tilt Servo 1 Tilt Angle at Maximum. -Defines the tilt angle when the servo is at the maximum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23317,8 +21203,7 @@ An angle of zero means upwards. Tilt Servo 1 Tilt Angle at Minimum. -Defines the tilt angle when the servo is at the minimum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23328,9 +21213,7 @@ An angle of zero means upwards. Tilt Servo 1 Tilt Direction. -Defines the direction the servo tilts towards when moving towards the maximum tilt angle. -For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', -the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. +Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. **Values:** @@ -23362,8 +21245,7 @@ Define if this servo is used for additional control. Tilt Servo 2 Tilt Angle at Maximum. -Defines the tilt angle when the servo is at the maximum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23373,8 +21255,7 @@ An angle of zero means upwards. Tilt Servo 2 Tilt Angle at Minimum. -Defines the tilt angle when the servo is at the minimum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23384,9 +21265,7 @@ An angle of zero means upwards. Tilt Servo 2 Tilt Direction. -Defines the direction the servo tilts towards when moving towards the maximum tilt angle. -For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', -the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. +Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. **Values:** @@ -23418,8 +21297,7 @@ Define if this servo is used for additional control. Tilt Servo 3 Tilt Angle at Maximum. -Defines the tilt angle when the servo is at the maximum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the maximum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23429,8 +21307,7 @@ An angle of zero means upwards. Tilt Servo 3 Tilt Angle at Minimum. -Defines the tilt angle when the servo is at the minimum. -An angle of zero means upwards. +Defines the tilt angle when the servo is at the minimum. An angle of zero means upwards. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23440,9 +21317,7 @@ An angle of zero means upwards. Tilt Servo 3 Tilt Direction. -Defines the direction the servo tilts towards when moving towards the maximum tilt angle. -For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', -the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. +Defines the direction the servo tilts towards when moving towards the maximum tilt angle. For example if the minimum tilt angle is -90, the maximum 90, and the direction 'Towards Front', the motor axis aligns with the XZ-plane, points towards -X at the minimum and +X at the maximum tilt. **Values:** @@ -23473,8 +21348,7 @@ Total number of Tilt Servos. Servo 1 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23484,8 +21358,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 2 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23495,8 +21368,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 3 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23506,8 +21378,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 4 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23517,8 +21388,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 5 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23528,8 +21398,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 6 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23539,8 +21408,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 7 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23550,8 +21418,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 8 Angle at Maximum. -Defines the angle when the servo is at the maximum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. +Defines the angle when the servo is at the maximum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MAXA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23561,8 +21428,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 1 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23572,8 +21438,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 2 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23583,8 +21448,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 3 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23594,8 +21458,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 4 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23605,8 +21468,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 5 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23616,8 +21478,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 6 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23627,8 +21488,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 7 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23638,8 +21498,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Servo 8 Angle at Minimum. -Defines the angle when the servo is at the minimum. -Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. +Defines the angle when the servo is at the minimum. Currently only supported in gz simulation and must be coherent with .sdf file and CA_SV_TL{n}\_MINA. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23651,8 +21510,7 @@ Currently only supported in gz simulation and must be coherent with .sdf file an Gate size for acceleration fusion. -Sets the number of standard deviations used -by the innovation consistency test. +Sets the number of standard deviations used by the innovation consistency test. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23662,8 +21520,7 @@ by the innovation consistency test. 1-sigma initial hover thrust uncertainty. -Sets the number of standard deviations used -by the innovation consistency test. +Sets the number of standard deviations used by the innovation consistency test. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----------------- | @@ -23673,9 +21530,7 @@ by the innovation consistency test. Hover thrust process noise. -Reduce to make the hover thrust estimate -more stable, increase if the real hover thrust -is expected to change quickly over time. +Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------------------- | @@ -23685,10 +21540,7 @@ is expected to change quickly over time. Max deviation from MPC_THR_HOVER. -Defines the range of the hover thrust estimate around MPC_THR_HOVER. -A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. -Set to a large value if the vehicle operates in varying physical conditions that -affect the required hover thrust strongly (e.g. differently sized payloads). +Defines the range of the hover thrust estimate around MPC_THR_HOVER. A value of 0.2 with MPC_THR_HOVER at 0.5 results in a range of [0.3, 0.7]. Set to a large value if the vehicle operates in varying physical conditions that affect the required hover thrust strongly (e.g. differently sized payloads). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----------------- | @@ -23698,9 +21550,7 @@ affect the required hover thrust strongly (e.g. differently sized payloads). Horizontal velocity threshold for sensitivity reduction. -Above this speed, the measurement noise is linearly increased -to reduce the sensitivity of the estimator from biased measurement. -Set to a low value on vehicles with large lifting surfaces. +Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles with large lifting surfaces. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23710,9 +21560,7 @@ Set to a low value on vehicles with large lifting surfaces. Vertical velocity threshold for sensitivity reduction. -Above this speed, the measurement noise is linearly increased -to reduce the sensitivity of the estimator from biased measurement. -Set to a low value on vehicles affected by air drag when climbing or descending. +Above this speed, the measurement noise is linearly increased to reduce the sensitivity of the estimator from biased measurement. Set to a low value on vehicles affected by air drag when climbing or descending. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23732,9 +21580,9 @@ Duration of choking during startup. Enable internal combustion engine. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | ### ICE_IGN_DELAY (`FLOAT`) {#ICE_IGN_DELAY} @@ -23763,7 +21611,6 @@ Engine start/stop input source. - `0`: On arming - disarming - `1`: Aux1 - `2`: Aux2 -- `3`: On Vtol Transitions | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23773,8 +21620,7 @@ Engine start/stop input source. Fault detection if it stops in running state. -Enables restart if a fault is detected during the running state. Otherwise -commands continues in running state until given an user request off. +Enables restart if a fault is detected during the running state. Otherwise commands continues in running state until given an user request off. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -23897,8 +21743,7 @@ Maximum airspeed allowed in the landed state Fixed-wing land detector: max rotational speed. -Maximum allowed norm of the angular velocity in the landed state. -Only used if neither airspeed nor groundspeed can be used for landing detection. +Maximum allowed norm of the angular velocity in the landed state. Only used if neither airspeed nor groundspeed can be used for landing detection. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -23918,9 +21763,7 @@ Time the land conditions (speeds and acceleration) have to be satisfied to detec Fixed-wing land detector: Max horizontal velocity threshold. -Maximum horizontal velocity allowed in the landed state. -A factor of 0.7 is applied in case of airspeed-less flying -(either because no sensor is present or sensor data got invalid in flight). +Maximum horizontal velocity allowed in the landed state. A factor of 0.7 is applied in case of airspeed-less flying (either because no sensor is present or sensor data got invalid in flight). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23950,8 +21793,7 @@ Maximum horizontal (x,y body axes) acceleration allowed in the landed state Ground effect altitude for multicopters. -The height above ground below which ground effect creates barometric altitude errors. -A negative value indicates no ground effect. +The height above ground below which ground effect creates barometric altitude errors. A negative value indicates no ground effect. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23971,9 +21813,7 @@ Maximum allowed norm of the angular velocity (roll, pitch) in the landed state. Multicopter land detection trigger time. -Total time it takes to go through all three land detection stages: -ground contact, maybe landed, landed -when all necessary conditions are constantly met. +Total time it takes to go through all three land detection stages: ground contact, maybe landed, landed when all necessary conditions are constantly met. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -23993,10 +21833,7 @@ Maximum horizontal velocity allowed in the landed state Multicopter vertical velocity threshold. -Vertical velocity threshold to detect landing. -Has to be set lower than the expected minimal speed for landing, -which is either MPC_LAND_SPEED or MPC_LAND_CRWL. -This is enforced by an automatic check. +Vertical velocity threshold to detect landing. Has to be set lower than the expected minimal speed for landing, which is either MPC_LAND_SPEED or MPC_LAND_CRWL. This is enforced by an automatic check. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -24006,8 +21843,7 @@ This is enforced by an automatic check. Total flight time in microseconds. -Total flight time of this autopilot. Higher 32 bits of the value. -Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. +Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -24017,8 +21853,7 @@ Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. Total flight time in microseconds. -Total flight time of this autopilot. Lower 32 bits of the value. -Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. +Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -24030,8 +21865,7 @@ Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO. Acceleration uncertainty. -Variance of acceleration measurement used for landing target position prediction. -Higher values results in tighter following of the measurements and more lenient outlier rejection +Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | --------- | @@ -24041,8 +21875,7 @@ Higher values results in tighter following of the measurements and more lenient Landing target measurement uncertainty. -Variance of the landing target measurement from the driver. -Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. +Variance of the landing target measurement from the driver. Higher values result in less aggressive following of the measurement and a smoother output as well as fewer rejected measurements. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---------- | @@ -24052,9 +21885,7 @@ Higher values result in less aggressive following of the measurement and a smoot Landing target mode. -Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. -Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. -Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. +Configure the mode of the landing target. Depending on the mode, the landing target observations are used differently to aid position estimation. Mode Moving: The landing target may be moving around while in the field of view of the vehicle. Landing target measurements are not used to aid positioning. Mode Stationary: The landing target is stationary. Measured velocity w.r.t. the landing target is used to aid velocity estimation. **Values:** @@ -24156,8 +21987,7 @@ Initial variance of the relative landing target velocity in x and y directions Accelerometer xy noise density. -Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) -Larger than data sheet to account for tilt error. +Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | -------------- | @@ -24267,16 +22097,7 @@ Optical flow scale. Integer bitmask controlling data fusion. -Set bits in the following positions to enable: -0 : Set to true to fuse GPS data if available, also requires GPS for altitude init -1 : Set to true to fuse optical flow data if available -2 : Set to true to fuse vision position -3 : Set to true to enable landing target -4 : Set to true to fuse land detector -5 : Set to true to publish AGL as local position down component -6 : Set to true to enable flow gyro compensation -7 : Set to true to enable baro fusion -default (145 - GPS, baro, land detector) +Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector) **Bitmask:** @@ -24403,8 +22224,7 @@ Accel bias propagation noise density. Position propagation noise density. -Increase to trust measurements more. -Decrease to trust model more. +Increase to trust measurements more. Decrease to trust model more. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------------ | @@ -24422,8 +22242,7 @@ Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001). Velocity propagation noise density. -Increase to trust measurements more. -Decrease to trust model more. +Increase to trust measurements more. Decrease to trust model more. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | -------------- | @@ -24519,8 +22338,7 @@ Required z standard deviation to publish altitude/ terrain. Broadcast heartbeats on local network for MAVLink instance 0. -This allows a ground control station to automatically find the drone -on the local network. +This allows a ground control station to automatically find the drone on the local network. **Values:** @@ -24562,8 +22380,7 @@ Configure on which serial port to run MAVLink. Enable serial flow control for instance 0. -This is used to force flow control on or off for the the mavlink -instance. By default it is auto detected. Use when auto detection fails. +This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails. **Values:** @@ -24579,10 +22396,7 @@ instance. By default it is auto detected. Use when auto detection fails. Enable MAVLink Message forwarding for instance 0. -If enabled, forward incoming MAVLink messages to other MAVLink ports if the -message is either broadcast or the target is not the autopilot. -This allows for example a GCS to talk to a camera that is connected to the -autopilot via MAVLink (on a different link than the GCS). +If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -24592,9 +22406,7 @@ autopilot via MAVLink (on a different link than the GCS). Configures the frequency of HIGH_LATENCY2 stream for instance 0. -Positive real value that configures the transmission frequency of the -HIGH_LATENCY2 stream for instance 0, configured in iridium mode. -This parameter has no effect if the instance mode is different from iridium. +Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 0, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24604,8 +22416,7 @@ This parameter has no effect if the instance mode is different from iridium. MAVLink Mode for instance 0. -The MAVLink Mode defines the set of streamed messages (for example the -vehicle's attitude) and their sending rates. +The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. **Values:** @@ -24630,9 +22441,7 @@ vehicle's attitude) and their sending rates. Enable software throttling of mavlink on instance 0. -If enabled, MAVLink messages will be throttled according to -`txbuf` field reported by radio_status. -Requires a radio to send the mavlink message RADIO_STATUS. +If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -24642,12 +22451,7 @@ Requires a radio to send the mavlink message RADIO_STATUS. Maximum MAVLink sending rate for instance 0. -Configure the maximum sending rate for the MAVLink streams in Bytes/sec. -If the configured streams exceed the maximum rate, the sending rate of -each stream is automatically decreased. -If this is set to 0 a value of half of the theoretical maximum bandwidth is used. -This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on -8N1-configured links). +Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24657,8 +22461,7 @@ This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on MAVLink Remote Port for instance 0. -If ethernet enabled and selected as configuration for MAVLink instance 0, -selected remote port will be set and used in MAVLink instance 0. +If ethernet enabled and selected as configuration for MAVLink instance 0, selected remote port will be set and used in MAVLink instance 0. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24668,8 +22471,7 @@ selected remote port will be set and used in MAVLink instance 0. MAVLink Network Port for instance 0. -If ethernet enabled and selected as configuration for MAVLink instance 0, -selected udp port will be set and used in MAVLink instance 0. +If ethernet enabled and selected as configuration for MAVLink instance 0, selected udp port will be set and used in MAVLink instance 0. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24679,8 +22481,7 @@ selected udp port will be set and used in MAVLink instance 0. Broadcast heartbeats on local network for MAVLink instance 1. -This allows a ground control station to automatically find the drone -on the local network. +This allows a ground control station to automatically find the drone on the local network. **Values:** @@ -24722,8 +22523,7 @@ Configure on which serial port to run MAVLink. Enable serial flow control for instance 1. -This is used to force flow control on or off for the the mavlink -instance. By default it is auto detected. Use when auto detection fails. +This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails. **Values:** @@ -24739,10 +22539,7 @@ instance. By default it is auto detected. Use when auto detection fails. Enable MAVLink Message forwarding for instance 1. -If enabled, forward incoming MAVLink messages to other MAVLink ports if the -message is either broadcast or the target is not the autopilot. -This allows for example a GCS to talk to a camera that is connected to the -autopilot via MAVLink (on a different link than the GCS). +If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -24752,9 +22549,7 @@ autopilot via MAVLink (on a different link than the GCS). Configures the frequency of HIGH_LATENCY2 stream for instance 1. -Positive real value that configures the transmission frequency of the -HIGH_LATENCY2 stream for instance 1, configured in iridium mode. -This parameter has no effect if the instance mode is different from iridium. +Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 1, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24764,8 +22559,7 @@ This parameter has no effect if the instance mode is different from iridium. MAVLink Mode for instance 1. -The MAVLink Mode defines the set of streamed messages (for example the -vehicle's attitude) and their sending rates. +The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. **Values:** @@ -24790,9 +22584,7 @@ vehicle's attitude) and their sending rates. Enable software throttling of mavlink on instance 1. -If enabled, MAVLink messages will be throttled according to -`txbuf` field reported by radio_status. -Requires a radio to send the mavlink message RADIO_STATUS. +If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -24802,12 +22594,7 @@ Requires a radio to send the mavlink message RADIO_STATUS. Maximum MAVLink sending rate for instance 1. -Configure the maximum sending rate for the MAVLink streams in Bytes/sec. -If the configured streams exceed the maximum rate, the sending rate of -each stream is automatically decreased. -If this is set to 0 a value of half of the theoretical maximum bandwidth is used. -This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on -8N1-configured links). +Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24817,8 +22604,7 @@ This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on MAVLink Remote Port for instance 1. -If ethernet enabled and selected as configuration for MAVLink instance 1, -selected remote port will be set and used in MAVLink instance 1. +If ethernet enabled and selected as configuration for MAVLink instance 1, selected remote port will be set and used in MAVLink instance 1. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24828,8 +22614,7 @@ selected remote port will be set and used in MAVLink instance 1. MAVLink Network Port for instance 1. -If ethernet enabled and selected as configuration for MAVLink instance 1, -selected udp port will be set and used in MAVLink instance 1. +If ethernet enabled and selected as configuration for MAVLink instance 1, selected udp port will be set and used in MAVLink instance 1. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24839,8 +22624,7 @@ selected udp port will be set and used in MAVLink instance 1. Broadcast heartbeats on local network for MAVLink instance 2. -This allows a ground control station to automatically find the drone -on the local network. +This allows a ground control station to automatically find the drone on the local network. **Values:** @@ -24882,8 +22666,7 @@ Configure on which serial port to run MAVLink. Enable serial flow control for instance 2. -This is used to force flow control on or off for the the mavlink -instance. By default it is auto detected. Use when auto detection fails. +This is used to force flow control on or off for the the mavlink instance. By default it is auto detected. Use when auto detection fails. **Values:** @@ -24899,10 +22682,7 @@ instance. By default it is auto detected. Use when auto detection fails. Enable MAVLink Message forwarding for instance 2. -If enabled, forward incoming MAVLink messages to other MAVLink ports if the -message is either broadcast or the target is not the autopilot. -This allows for example a GCS to talk to a camera that is connected to the -autopilot via MAVLink (on a different link than the GCS). +If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -24912,9 +22692,7 @@ autopilot via MAVLink (on a different link than the GCS). Configures the frequency of HIGH_LATENCY2 stream for instance 2. -Positive real value that configures the transmission frequency of the -HIGH_LATENCY2 stream for instance 2, configured in iridium mode. -This parameter has no effect if the instance mode is different from iridium. +Positive real value that configures the transmission frequency of the HIGH_LATENCY2 stream for instance 2, configured in iridium mode. This parameter has no effect if the instance mode is different from iridium. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24924,8 +22702,7 @@ This parameter has no effect if the instance mode is different from iridium. MAVLink Mode for instance 2. -The MAVLink Mode defines the set of streamed messages (for example the -vehicle's attitude) and their sending rates. +The MAVLink Mode defines the set of streamed messages (for example the vehicle's attitude) and their sending rates. **Values:** @@ -24950,9 +22727,7 @@ vehicle's attitude) and their sending rates. Enable software throttling of mavlink on instance 2. -If enabled, MAVLink messages will be throttled according to -`txbuf` field reported by radio_status. -Requires a radio to send the mavlink message RADIO_STATUS. +If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -24962,12 +22737,7 @@ Requires a radio to send the mavlink message RADIO_STATUS. Maximum MAVLink sending rate for instance 2. -Configure the maximum sending rate for the MAVLink streams in Bytes/sec. -If the configured streams exceed the maximum rate, the sending rate of -each stream is automatically decreased. -If this is set to 0 a value of half of the theoretical maximum bandwidth is used. -This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on -8N1-configured links). +Configure the maximum sending rate for the MAVLink streams in Bytes/sec. If the configured streams exceed the maximum rate, the sending rate of each stream is automatically decreased. If this is set to 0 a value of half of the theoretical maximum bandwidth is used. This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on 8N1-configured links). | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24977,8 +22747,7 @@ This corresponds to baudrate/20 Bytes/s (baudrate/10 = maximum data rate on MAVLink Remote Port for instance 2. -If ethernet enabled and selected as configuration for MAVLink instance 2, -selected remote port will be set and used in MAVLink instance 2. +If ethernet enabled and selected as configuration for MAVLink instance 2, selected remote port will be set and used in MAVLink instance 2. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -24988,8 +22757,7 @@ selected remote port will be set and used in MAVLink instance 2. MAVLink Network Port for instance 2. -If ethernet enabled and selected as configuration for MAVLink instance 2, -selected udp port will be set and used in MAVLink instance 2. +If ethernet enabled and selected as configuration for MAVLink instance 2, selected udp port will be set and used in MAVLink instance 2. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -25007,8 +22775,7 @@ MAVLink component ID. Forward external setpoint messages. -If set to 1 incoming external setpoint messages will be directly forwarded -to the controllers if in offboard control mode +If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -25018,8 +22785,7 @@ to the controllers if in offboard control mode Parameter hash check. -Disabling the parameter hash check functionality will make the mavlink instance -stream parameters continuously. +Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -25029,8 +22795,7 @@ stream parameters continuously. Heartbeat message forwarding. -The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. -The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. +The mavlink heartbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -25042,20 +22807,19 @@ MAVLink protocol version. **Values:** -- `1`: Version 1 with auto-upgrade to v2 if detected -- `2`: Version 2 +- `0`: Default to 1, switch to 2 if GCS sends version 2 +- `1`: Always use version 1 +- `2`: Always use version 2 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 2 | +|   | | | | 0 | ### MAV_RADIO_TOUT (`INT32`) {#MAV_RADIO_TOUT} Timeout in seconds for the RADIO_STATUS reports coming in. -If the connected radio stops reporting RADIO_STATUS for a certain time, -a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow -control is reset. +If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25065,10 +22829,7 @@ control is reset. MAVLink SiK Radio ID. -When non-zero the MAVLink app will attempt to configure the -SiK radio to this ID and re-set the parameter to 0. If the value -is negative it will reset the complete radio config to -factory defaults. Only applies if this mavlink instance is going through a SiK radio +When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25082,36 +22843,6 @@ MAVLink system ID. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | 1 | 250 | | 1 | -### MAV_S_FORWARD (`INT32`) {#MAV_S_FORWARD} - -Enable MAVLink forwarding on TELEM2. - -TELEM2 on Skynode only. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - -### MAV_S_MODE (`INT32`) {#MAV_S_MODE} - -MAVLink Mode for SOM to FMU communication channel. - -The MAVLink Mode defines the set of streamed messages (for example the -vehicle's attitude) and their sending rates. - -**Values:** - -- `0`: Normal -- `2`: Onboard -- `5`: Config -- `7`: Minimal -- `11`: Onboard Low Bandwidth -- `13`: Low Bandwidth - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 11 | - ### MAV_TYPE (`INT32`) {#MAV_TYPE} MAVLink airframe type. @@ -25208,8 +22939,7 @@ Defines which ODR rate to use during data polling. Enable online mag bias calibration. -This enables continuous calibration of the magnetometers -before takeoff using gyro data. +This enables continuous calibration of the magnetometers before takeoff using gyro data. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -25219,8 +22949,7 @@ before takeoff using gyro data. Mag bias estimator learning gain. -Increase to make the estimator more responsive -Decrease to make the estimator more robust to noise +Increase to make the estimator more responsive Decrease to make the estimator more robust to noise | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25232,34 +22961,17 @@ Decrease to make the estimator more robust to noise Enable arm/disarm stick gesture. -This determines if moving the left stick to the lower right -arms and to the lower left disarms the vehicle. +This determines if moving the left stick to the lower right arms and to the lower left disarms the vehicle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | |   | | | | Enabled (1) | -### MAN_DEADZONE (`FLOAT`) {#MAN_DEADZONE} - -Deadzone for sticks (only specific use cases). - -Range around stick center ignored to prevent -vehicle drift from stick hardware inaccuracy. -Does not apply to any precise constant input like -throttle and attitude or rate piloting. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.1 | - ### MAN_KILL_GEST_T (`FLOAT`) {#MAN_KILL_GEST_T} Trigger time for kill stick gesture. -The timeout for holding the left stick to the lower left -and the right stick to the lower right at the same time until the gesture -kills the actuators one-way. -A negative value disables the feature. +The timeout for holding the left stick to the lower left and the right stick to the lower right at the same time until the gesture kills the actuators one-way. A negative value disables the feature. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25271,13 +22983,7 @@ A negative value disables the feature. Timeout to allow the payload to execute the mission command. -Ensure: -gripper: NAV_CMD_DO_GRIPPER -has released before continuing mission. -winch: CMD_DO_WINCH -has delivered before continuing mission. -gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW -has reached the commanded orientation before beginning to take pictures. +Ensure: gripper: NAV_CMD_DO_GRIPPER has released before continuing mission. winch: CMD_DO_WINCH has delivered before continuing mission. gimbal: CMD_DO_GIMBAL_MANAGER_PITCHYAW has reached the commanded orientation before beginning to take pictures. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25287,9 +22993,7 @@ has reached the commanded orientation before beginning to take pictures. Maximal horizontal distance from Home to first waypoint. -There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. -Has no effect on mission validity. -Set a value of zero or less to disable. +There will be a warning message if the current waypoint is more distant than MIS_DIST_1WP from Home. Has no effect on mission validity. Set a value of zero or less to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25299,9 +23003,7 @@ Set a value of zero or less to disable. Landing abort min altitude. -Minimum altitude above landing point that the vehicle will climb to after an aborted landing. -Then vehicle will loiter in this altitude until further command is received. -Only applies to fixed-wing vehicles. +Minimum altitude above landing point that the vehicle will climb to after an aborted landing. Then vehicle will loiter in this altitude until further command is received. Only applies to fixed-wing vehicles. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25311,8 +23013,7 @@ Only applies to fixed-wing vehicles. Enable yaw control of the mount. (Only affects multicopters and ROI mission items). -If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. -If disabled, the vehicle will yaw towards the ROI. +If enabled, yaw commands will be sent to the mount and the vehicle will follow its heading towards the flight direction. If disabled, the vehicle will yaw towards the ROI. **Values:** @@ -25327,8 +23028,7 @@ If disabled, the vehicle will yaw towards the ROI. Default take-off altitude. -This is the relative altitude the system will take off to -if not otherwise specified. +This is the relative altitude the system will take off to if not otherwise specified. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25338,8 +23038,7 @@ if not otherwise specified. Mission takeoff/landing required. -Specifies if a mission has to contain a takeoff and/or mission landing. -Validity of configured takeoffs/landings is checked independently of the setting here. +Specifies if a mission has to contain a takeoff and/or mission landing. Validity of configured takeoffs/landings is checked independently of the setting here. **Values:** @@ -25366,10 +23065,7 @@ Max yaw error in degrees needed for waypoint heading acceptance. Time in seconds we wait on reaching target heading at a waypoint if it is forced. -If set > 0 it will ignore the target heading for normal waypoint acceptance. If the -waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. -Mainly useful for VTOLs that have less yaw authority and might not reach target -yaw in wind. Disabled by default. +If set > 0 it will ignore the target heading for normal waypoint acceptance. If the waypoint forces the heading the timeout will matter. For example on VTOL forwards transition. Mainly useful for VTOLs that have less yaw authority and might not reach target yaw in wind. Disabled by default. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25396,8 +23092,7 @@ Heading behavior in autonomous modes. Acceptance Radius. -Default acceptance radius, overridden by acceptance radius of waypoint if set. -For fixed wing the npfg switch distance is used for horizontal acceptance. +Default acceptance radius, overridden by acceptance radius of waypoint if set. For fixed wing the npfg switch distance is used for horizontal acceptance. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25415,8 +23110,7 @@ Force VTOL mode takeoff and land. FW Altitude Acceptance Radius before a landing. -Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller -than the standard vertical acceptance because close to the ground higher accuracy is required. +Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25436,13 +23130,11 @@ Acceptance radius for fixedwing altitude. Loiter radius (FW only). -Default value of loiter radius in fixed-wing mode (e.g. for Loiter mode). -The direction of the loiter can be set via the sign: A positive value for -clockwise, negative for counter-clockwise. +Default value of loiter radius in FW mode (e.g. for Loiter mode). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -10000 | 10000 | 0.5 | 80.0 | m | +|   | 25 | 1000 | 0.5 | 80.0 | m | ### NAV_MC_ALT_RAD (`FLOAT`) {#NAV_MC_ALT_RAD} @@ -25458,11 +23150,7 @@ Acceptance radius for multicopter altitude. Minimum height above ground during Mission and RTL. -Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, -excluding landing commands. -Requires a distance sensor to be set up. -Note: only prevents the vehicle from descending further, but does not force it to climb. -Set to a negative value to disable. +Minimum height above ground the vehicle is allowed to descend to during Mission and RTL, excluding landing commands. Requires a distance sensor to be set up. Note: only prevents the vehicle from descending further, but does not force it to climb. Set to a negative value to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25472,10 +23160,7 @@ Set to a negative value to disable. Minimum Loiter altitude. -This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this -mode without specifying an altitude (e.g. through Loiter switch on RC). -Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint ("Go to"). -Set to a negative value to disable. +This is the minimum altitude above Home the system will always obey in Loiter (Hold) mode if switched into this mode without specifying an altitude (e.g. through Loiter switch on RC). Doesn't affect Loiters that are part of Missions or that are entered through a reposition setpoint ("Go to"). Set to a negative value to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25485,8 +23170,7 @@ Set to a negative value to disable. Set traffic avoidance mode. -Enabling this will allow the system to respond -to transponder data from e.g. ADSB transponders +Enabling this will allow the system to respond to transponder data from e.g. ADSB transponders **Values:** @@ -25522,8 +23206,7 @@ Set NAV TRAFFIC AVOID vertical distance. Estimated time until collision. -Minimum acceptable time until collsion. -Assumes constant speed over 3d distance. +Minimum acceptable time until collsion. Assumes constant speed over 3d distance. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | --------- | --------- | ------- | ---- | @@ -25535,11 +23218,7 @@ Assumes constant speed over 3d distance. Multicopter air-mode. -The air-mode enables the mixer to increase the total thrust of the multirotor -in order to keep attitude and rate control even at low and high throttle. -This function should be disabled during tuning as it will help the controller -to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). -Enabling air-mode for yaw requires the use of an arming switch. +The air-mode enables the mixer to increase the total thrust of the multirotor in order to keep attitude and rate control even at low and high throttle. This function should be disabled during tuning as it will help the controller to diverge if the closed-loop is unstable (i.e. the vehicle is not tuned yet). Enabling air-mode for yaw requires the use of an arming switch. **Values:** @@ -25557,8 +23236,7 @@ Enabling air-mode for yaw requires the use of an arming switch. Custom configuration for ModalAI drones. -This can be set to indicate that drone behavior -needs to be changed to match a custom setting +This can be set to indicate that drone behavior needs to be changed to match a custom setting | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -25570,9 +23248,7 @@ needs to be changed to match a custom setting Stabilize the mount. -Set to true for servo gimbal, false for passthrough. -This is required for a gimbal which is not capable of stabilizing itself -and relies on the IMU's attitude estimation. +Set to true for servo gimbal, false for passthrough. This is required for a gimbal which is not capable of stabilizing itself and relies on the IMU's attitude estimation. **Values:** @@ -25678,9 +23354,7 @@ If MNT_MODE_OUT is MAVLink gimbal protocol v1, mount configure/control commands Mount input mode. -This is the protocol used between the ground station and the autopilot. -Recommended is Auto, RC only or MAVLink gimbal protocol v2. -The rest will be deprecated. +This is the protocol used between the ground station and the autopilot. Recommended is Auto, RC only or MAVLink gimbal protocol v2. The rest will be deprecated. **Values:** @@ -25699,8 +23373,7 @@ The rest will be deprecated. Mount output mode. -This is the protocol used between the autopilot and a connected gimbal. -Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it. +This is the protocol used between the autopilot and a connected gimbal. Recommended is the MAVLink gimbal protocol v2 if the gimbal supports it. **Values:** @@ -25799,9 +23472,7 @@ Input mode for RC gimbal input. Acro mode roll, pitch expo factor. -Exponential factor for tuning the input curve shape. -0 Purely linear input curve -1 Purely cubic input curve +Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25811,9 +23482,7 @@ Exponential factor for tuning the input curve shape. Acro mode yaw expo factor. -Exponential factor for tuning the input curve shape. -0 Purely linear input curve -1 Purely cubic input curve +Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25843,10 +23512,7 @@ Full stick deflection leads to this rate. Acro mode roll, pitch super expo factor. -"Superexponential" factor for refining the input curve shape tuned using MC_ACRO_EXPO. -0 Pure Expo function -0.7 reasonable shape enhancement for intuitive stick feel -0.95 very strong bent input curve only near maxima have effect +"Superexponential" factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25856,10 +23522,7 @@ Acro mode roll, pitch super expo factor. Acro mode yaw super expo factor. -"Superexponential" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. -0 Pure Expo function -0.7 reasonable shape enhancement for intuitive stick feel -0.95 very strong bent input curve only near maxima have effect +"Superexponential" factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 reasonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25881,11 +23544,7 @@ Full stick deflection leads to this rate. Max pitch rate. -Limit for pitch rate in manual and auto modes (except acro). -Has effect for large rotations in autonomous mode, to avoid large control -output and mixer saturation. -This is not only limited by the vehicle's properties, but also by the maximum -measurement rate of the gyro. +Limit for pitch rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -25899,17 +23558,13 @@ Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 12 | 0.1 | 4.0 | +|   | 0.0 | 12 | 0.1 | 6.5 | ### MC_ROLLRATE_MAX (`FLOAT`) {#MC_ROLLRATE_MAX} Max roll rate. -Limit for roll rate in manual and auto modes (except acro). -Has effect for large rotations in autonomous mode, to avoid large control -output and mixer saturation. -This is not only limited by the vehicle's properties, but also by the maximum -measurement rate of the gyro. +Limit for roll rate in manual and auto modes (except acro). Has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation. This is not only limited by the vehicle's properties, but also by the maximum measurement rate of the gyro. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -25923,7 +23578,7 @@ Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 12 | 0.1 | 4.0 | +|   | 0.0 | 12 | 0.1 | 6.5 | ### MC_YAWRATE_MAX (`FLOAT`) {#MC_YAWRATE_MAX} @@ -25947,11 +23602,7 @@ Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. Yaw weight. -A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. -Deprioritizing yaw is necessary because multicopters have much less control authority -in yaw compared to the other axes and it makes sense because yaw is not critical for -stable hovering or 3D navigation. -For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain. +A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. Deprioritizing yaw is necessary because multicopters have much less control authority in yaw compared to the other axes and it makes sense because yaw is not critical for stable hovering or 3D navigation. For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -25961,8 +23612,7 @@ For yaw control tuning use MC_YAW_P. This ratio has no impact on the yaw gain. Maximum yaw acceleration in autonomous modes. -Limits the acceleration of the yaw setpoint to avoid large -control output and mixer saturation. +Limits the acceleration of the yaw setpoint to avoid large control output and mixer saturation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------- | @@ -25972,8 +23622,7 @@ control output and mixer saturation. Maximum yaw rate in autonomous modes. -Limits the rate of change of the yaw setpoint to avoid large -control output and mixer saturation. +Limits the rate of change of the yaw setpoint to avoid large control output and mixer saturation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -26035,9 +23684,7 @@ Setting this parameter to 0 disables the filter Acceleration to tilt coupling. -Set to decouple tilt from vertical acceleration. -This provides smoother flight but slightly worse tracking in position and auto modes. -Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight. +Set to decouple tilt from vertical acceleration. This provides smoother flight but slightly worse tracking in position and auto modes. Unset if accurate position tracking during dynamic maneuvers is more important than a smooth flight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -26065,9 +23712,7 @@ When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration Maximum horizontal acceleration. -MPC_POS_MODE -1 just deceleration -4 not used, use MPC_ACC_HOR instead +MPC_POS_MODE 1 just deceleration 4 not used, use MPC_ACC_HOR instead | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -26085,13 +23730,7 @@ Maximum upwards acceleration in climb rate controlled modes. Altitude reference mode. -Control height -0: relative earth frame origin which may drift due to sensors -1: relative to ground (requires distance sensor) which changes with terrain variation. -It will revert to relative earth frame if the distance to ground estimate becomes invalid. -2: relative to ground (requires distance sensor) when stationary -and relative to earth frame when moving horizontally. -The speed threshold is MPC_HOLD_MAX_XY +Control height 0: relative earth frame origin which may drift due to sensors 1: relative to ground (requires distance sensor) which changes with terrain variation. It will revert to relative earth frame if the distance to ground estimate becomes invalid. 2: relative to ground (requires distance sensor) when stationary and relative to earth frame when moving horizontally. The speed threshold is MPC_HOLD_MAX_XY **Values:** @@ -26103,6 +23742,16 @@ The speed threshold is MPC_HOLD_MAX_XY | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 2 | | 2 | +### MPC_HOLD_DZ (`FLOAT`) {#MPC_HOLD_DZ} + +Deadzone for sticks in manual piloted modes. + +Does not apply to manual throttle and direct attitude piloting by stick. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | 0.01 | 0.1 | + ### MPC_HOLD_MAX_XY (`FLOAT`) {#MPC_HOLD_MAX_XY} Maximum horizontal velocity for which position hold is enabled (use 0 to disable check). @@ -26127,8 +23776,7 @@ Only used with MPC_ALT_MODE 1 Jerk limit in autonomous modes. -Limit the maximum jerk of the vehicle (how fast the acceleration can change). -A lower value leads to smoother vehicle motions but also limited agility. +Limit the maximum jerk of the vehicle (how fast the acceleration can change). A lower value leads to smoother vehicle motions but also limited agility. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -26138,10 +23786,7 @@ A lower value leads to smoother vehicle motions but also limited agility. Maximum horizontal and vertical jerk in Position/Altitude mode. -Limit the maximum jerk (acceleration change) of the vehicle. -A lower value leads to smoother motions but limits agility. -Setting this to the maximum value essentially disables the limit. -Only used with MPC_POS_MODE Acceleration based. +Limit the maximum jerk (acceleration change) of the vehicle. A lower value leads to smoother motions but limits agility. Setting this to the maximum value essentially disables the limit. Only used with MPC_POS_MODE Acceleration based. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -26151,9 +23796,7 @@ Only used with MPC_POS_MODE Acceleration based. Altitude for 1. step of slow landing (descend). -Below this altitude descending velocity gets limited to a value -between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED" -Value needs to be higher than "MPC_LAND_ALT2" +Below this altitude descending velocity gets limited to a value between "MPC_Z_VEL_MAX_DN" (or "MPC_Z_V_AUTO_DN") and "MPC_LAND_SPEED" Value needs to be higher than "MPC_LAND_ALT2" | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26163,9 +23806,7 @@ Value needs to be higher than "MPC_LAND_ALT2" Altitude for 2. step of slow landing (landing). -Below this altitude descending velocity gets -limited to "MPC_LAND_SPEED" -Value needs to be lower than "MPC_LAND_ALT1" +Below this altitude descending velocity gets limited to "MPC_LAND_SPEED" Value needs to be lower than "MPC_LAND_ALT1" | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26175,8 +23816,7 @@ Value needs to be lower than "MPC_LAND_ALT1" Altitude for 3. step of slow landing. -If a valid distance sensor measurement to the ground is available, -limit descending velocity to "MPC_LAND_CRWL" below this altitude. +If a valid distance sensor measurement to the ground is available, limit descending velocity to "MPC_LAND_CRWL" below this altitude. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26196,27 +23836,17 @@ Used below MPC_LAND_ALT3 if distance sensor data is availabe. User assisted landing radius. -When nudging is enabled (see MPC_LAND_RC_HELP), this defines the maximum -allowed horizontal displacement from the original landing point. - -- If inside of the radius, only allow nudging inputs that do not move the vehicle outside of it. -- If outside of the radius, only allow nudging inputs that move the vehicle back towards it. - Set it to -1 for infinite radius. +When nudging is enabled (see MPC_LAND_RC_HELP), this controls the maximum allowed horizontal displacement from the original landing point. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | | 1 | -1.0 | m | +|   | 0 | | 1 | 1000. | m | ### MPC_LAND_RC_HELP (`INT32`) {#MPC_LAND_RC_HELP} Enable nudging based on user input during autonomous land routine. -Using stick input the vehicle can be moved horizontally and yawed. -The descend speed is amended: -stick full up - 0 -stick centered - MPC_LAND_SPEED -stick full down - 2 \* MPC_LAND_SPEED -Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE). +Using stick input the vehicle can be moved horizontally and yawed. The descend speed is amended: stick full up - 0 stick centered - MPC_LAND_SPEED stick full down - 2 \* MPC_LAND_SPEED Manual override during auto modes has to be disabled to use this feature (see COM_RC_OVERRIDE). **Values:** @@ -26239,9 +23869,7 @@ Landing descend rate. Minimum collective thrust in Stabilized mode. -The value is mapped to the lowest throttle stick position in Stabilized mode. -Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. -Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE). +The value is mapped to the lowest throttle stick position in Stabilized mode. Too low collective thrust leads to loss of roll/pitch/yaw torque control authority. Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26249,7 +23877,7 @@ Airmode is used to keep torque authority with zero thrust (see MC_AIRMODE). ### MPC_MAN_TILT_MAX (`FLOAT`) {#MPC_MAN_TILT_MAX} -Maximal tilt angle in Stabilized, Altitude and Altitude Cruise mode. +Maximal tilt angle in Stabilized or Altitude mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26267,8 +23895,7 @@ Max manual yaw rate for Stabilized, Altitude, Position mode. Manual yaw rate input filter time constant. -Not used in Stabilized mode -Setting this parameter to 0 disables the filter +Not used in Stabilized mode Setting this parameter to 0 disables the filter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26278,13 +23905,7 @@ Setting this parameter to 0 disables the filter Position/Altitude mode variant. -The supported sub-modes are: -Direct velocity: -Sticks directly map to velocity setpoints without smoothing. -Also applies to vertical direction and Altitude mode. -Useful for velocity control tuning. -Acceleration based: -Sticks map to acceleration and there's a virtual brake drag +The supported sub-modes are: Direct velocity: Sticks directly map to velocity setpoints without smoothing. Also applies to vertical direction and Altitude mode. Useful for velocity control tuning. Acceleration based: Sticks map to acceleration and there's a virtual brake drag **Values:** @@ -26299,15 +23920,7 @@ Sticks map to acceleration and there's a virtual brake drag Thrust curve mapping in Stabilized Mode. -Defines how the throttle stick is mapped to collective thrust in Stabilized mode. -Rescale to hover thrust estimate: -Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output. -No rescale: -Directly map the stick 1:1 to the output. -Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive. -Rescale to hover thrust parameter: -Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value. -With MPC_THR_HOVER 0.5 it's equivalent to No rescale. +Defines how the throttle stick is mapped to collective thrust in Stabilized mode. Rescale to hover thrust estimate: Stick input is linearly rescaled, such that a centered throttle stick corresponds to the hover thrust estimator's output. No rescale: Directly map the stick 1:1 to the output. Can be useful with very low hover thrust which leads to much distortion and the upper half getting sensitive. Rescale to hover thrust parameter: Similar to rescaling to the hover thrust estimate, but it uses the hover thrust parameter value (see MPC_THR_HOVER) instead of estimated value. With MPC_THR_HOVER 0.5 it's equivalent to No rescale. **Values:** @@ -26323,10 +23936,7 @@ With MPC_THR_HOVER 0.5 it's equivalent to No rescale. Vertical thrust required to hover. -Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). -Used for initialization of the hover thrust estimator (see MPC_USE_HTE). -The estimated hover thrust is used as base for zero vertical acceleration in altitude control. -The hover thrust is important for land detection to work correctly. +Mapped to center throttle stick in Stabilized mode (see MPC_THR_CURVE). Used for initialization of the hover thrust estimator (see MPC_USE_HTE). The estimated hover thrust is used as base for zero vertical acceleration in altitude control. The hover thrust is important for land detection to work correctly. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26346,9 +23956,7 @@ Limit allowed thrust e.g. for indoor test of overpowered vehicle. Minimum collective thrust in climb rate controlled modes. -Too low thrust leads to loss of roll/pitch/yaw torque control authority. -With airmode enabled this parameters can be set to 0 -while still keeping torque authority (see MC_AIRMODE). +Too low thrust leads to loss of roll/pitch/yaw torque control authority. With airmode enabled this parameters can be set to 0 while still keeping torque authority (see MC_AIRMODE). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26358,8 +23966,7 @@ while still keeping torque authority (see MC_AIRMODE). Horizontal thrust margin. -Margin that is kept for horizontal control when higher priority vertical thrust is saturated. -To avoid completely starving horizontal control with high vertical error. +Margin that is kept for horizontal control when higher priority vertical thrust is saturated. To avoid completely starving horizontal control with high vertical error. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26369,8 +23976,7 @@ To avoid completely starving horizontal control with high vertical error. Maximum tilt angle in air. -Absolute maximum for all velocity or acceleration controlled modes. -Any higher value is truncated. +Absolute maximum for all velocity or acceleration controlled modes. Any higher value is truncated. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26390,9 +23996,7 @@ Tighter tilt limit during takeoff to avoid tip over. Smooth takeoff ramp time constant. -Increasing this value will make climb rate controlled takeoff slower. -If it's too slow the drone might scratch the ground and tip over. -A time constant of 0 disables the ramp +Increasing this value will make climb rate controlled takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26410,8 +24014,7 @@ Takeoff climb rate. Use hover thrust estimate for altitude control. -Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller. -This parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE). +Disable to use the fixed parameter MPC_THR_HOVER instead of the hover thrust estimate in the position controller. This parameter does not influence Stabilized mode throttle curve (see MPC_THR_CURVE). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ----------- | ---- | @@ -26441,9 +24044,7 @@ A value of 0 disables the filter. Maximum horizontal velocity setpoint in Position mode. -Must be smaller than MPC_XY_VEL_MAX. -The maximum sideways and backward speed can be set differently -using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. +Must be smaller than MPC_XY_VEL_MAX. The maximum sideways and backward speed can be set differently using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26453,8 +24054,7 @@ using MPC_VEL_MAN_SIDE and MPC_VEL_MAN_BACK, respectively. Maximum backward velocity in Position mode. -If set to a negative value or larger than -MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. +If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26464,8 +24064,7 @@ MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. Maximum sideways velocity in Position mode. -If set to a negative value or larger than -MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. +If set to a negative value or larger than MPC_VEL_MANUAL then MPC_VEL_MANUAL is used. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26485,8 +24084,7 @@ A value of 0 disables the filter. Velocity notch filter frequency. -The center frequency for the 2nd order notch filter on the velocity. -A value of 0 disables the filter. +The center frequency for the 2nd order notch filter on the velocity. A value of 0 disables the filter. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26506,17 +24104,22 @@ e.g. in Missions, RTL, Goto if the waypoint does not specify differently Maximum horizontal error allowed by the trajectory generator. -The integration speed of the trajectory setpoint is linearly -reduced with the horizontal position tracking error. When the -error is above this parameter, the integration of the -trajectory is stopped to wait for the drone. -This value can be adjusted depending on the tracking -capabilities of the vehicle. +The integration speed of the trajectory setpoint is linearly reduced with the horizontal position tracking error. When the error is above this parameter, the integration of the trajectory is stopped to wait for the drone. This value can be adjusted depending on the tracking capabilities of the vehicle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 10 | 1 | 2. | +### MPC_XY_MAN_EXPO (`FLOAT`) {#MPC_XY_MAN_EXPO} + +Manual position control stick exponential curve sensitivity. + +The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | 0.01 | 0.6 | + ### MPC_XY_P (`FLOAT`) {#MPC_XY_P} Proportional gain for horizontal position error. @@ -26539,9 +24142,7 @@ Proportional gain for horizontal trajectory position error. Overall Horizontal Velocity Limit. -If set to a value greater than zero, other parameters are automatically set (such as -MPC_XY_VEL_MAX or MPC_VEL_MANUAL). -If set to a negative value, the existing individual parameters are used. +If set to a value greater than zero, other parameters are automatically set (such as MPC_XY_VEL_MAX or MPC_VEL_MANUAL). If set to a negative value, the existing individual parameters are used. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26561,8 +24162,7 @@ Defined as corrective acceleration in m/s^2 per m/s^2 velocity derivative Integral gain for horizontal velocity error. -Defined as correction acceleration in m/s^2 per m velocity integral -Allows to eliminate steady state errors in disturbances like wind. +Defined as correction acceleration in m/s^2 per m velocity integral Allows to eliminate steady state errors in disturbances like wind. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26572,8 +24172,7 @@ Allows to eliminate steady state errors in disturbances like wind. Maximum horizontal velocity. -Absolute maximum for all velocity controlled modes. -Any higher value is truncated. +Absolute maximum for all velocity controlled modes. Any higher value is truncated. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26589,6 +24188,26 @@ Defined as corrective acceleration in m/s^2 per m/s velocity error | ------ | -------- | -------- | --------- | ------- | ---- | |   | 1.2 | 5 | 0.1 | 1.8 | +### MPC_YAW_EXPO (`FLOAT`) {#MPC_YAW_EXPO} + +Manual control stick yaw rotation exponential curve. + +The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | 0.01 | 0.6 | + +### MPC_Z_MAN_EXPO (`FLOAT`) {#MPC_Z_MAN_EXPO} + +Manual control stick vertical exponential curve. + +The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve 1 Purely cubic input curve + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1 | 0.01 | 0.6 | + ### MPC_Z_P (`FLOAT`) {#MPC_Z_P} Proportional gain for vertical position error. @@ -26603,9 +24222,7 @@ Defined as corrective velocity in m/s per m position error Overall Vertical Velocity Limit. -If set to a value greater than zero, other parameters are automatically set (such as -MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). -If set to a negative value, the existing individual parameters are used. +If set to a value greater than zero, other parameters are automatically set (such as MPC_Z_VEL_MAX_UP or MPC_LAND_SPEED). If set to a negative value, the existing individual parameters are used. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26635,9 +24252,7 @@ Defined as corrective acceleration in m/s^2 per m velocity integral Maximum descent velocity. -Absolute maximum for all climb rate controlled modes. -In manually piloted modes full stick deflection commands this velocity. -For default autonomous velocity see MPC_Z_V_AUTO_UP +Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26647,9 +24262,7 @@ For default autonomous velocity see MPC_Z_V_AUTO_UP Maximum ascent velocity. -Absolute maximum for all climb rate controlled modes. -In manually piloted modes full stick deflection commands this velocity. -For default autonomous velocity see MPC_Z_V_AUTO_UP +Absolute maximum for all climb rate controlled modes. In manually piloted modes full stick deflection commands this velocity. For default autonomous velocity see MPC_Z_V_AUTO_UP | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26685,23 +24298,11 @@ For manually controlled modes and offboard see MPC_Z_VEL_MAX_UP | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.5 | 8 | 0.5 | 3. | m/s | -### SC_MAN_TILT_MAX (`FLOAT`) {#SC_MAN_TILT_MAX} - -Maximal tilt angle in Stabilized or Manual mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 90 | 1 | 90. | deg | - ### SYS_VEHICLE_RESP (`FLOAT`) {#SYS_VEHICLE_RESP} Responsiveness. -Changes the overall responsiveness of the vehicle. -The higher the value, the faster the vehicle will react. -If set to a value greater than zero, other parameters are automatically set (such as -the acceleration or jerk limits). -If set to a negative value, the existing individual parameters are used. +Changes the overall responsiveness of the vehicle. The higher the value, the faster the vehicle will react. If set to a value greater than zero, other parameters are automatically set (such as the acceleration or jerk limits). If set to a negative value, the existing individual parameters are used. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26737,9 +24338,7 @@ Maximum yawrate the weathervane controller is allowed to demand. Default horizontal velocity limit. -This value is used in slow mode if -no aux channel is mapped and -no limit is commanded through MAVLink. +This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26749,9 +24348,7 @@ no limit is commanded through MAVLink. Default vertical velocity limit. -This value is used in slow mode if -no aux channel is mapped and -no limit is commanded through MAVLink. +This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26761,9 +24358,7 @@ no limit is commanded through MAVLink. Default yaw rate limit. -This value is used in slow mode if -no aux channel is mapped and -no limit is commanded through MAVLink. +This value is used in slow mode if no aux channel is mapped and no limit is commanded through MAVLink. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -26877,11 +24472,7 @@ The lowest input maps and is clamped to this rate. Battery power level scaler. -This compensates for voltage drop of the battery over time by attempting to -normalize performance across the operating range of the battery. The copter -should constantly behave as if it was fully charged with reduced max acceleration -at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, -it will still be 0.5 at 60% battery. +This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -26921,14 +24512,7 @@ Pitch rate integral gain. Can be set to compensate static thrust difference or g Pitch rate controller gain. -Global gain of the controller. -This gain scales the P, I and D terms of the controller: -output = MC_PITCHRATE_K _ (MC_PITCHRATE_P _ error - -- MC_PITCHRATE_I \* error_integral -- MC_PITCHRATE_D \* error_derivative) - Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. - Set MC_PITCHRATE_K=1 to implement a PID in the parallel form. +Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K _ (MC_PITCHRATE_P _ error + MC_PITCHRATE_I _ error_integral + MC_PITCHRATE_D _ error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -26988,14 +24572,7 @@ Roll rate integral gain. Can be set to compensate static thrust difference or gr Roll rate controller gain. -Global gain of the controller. -This gain scales the P, I and D terms of the controller: -output = MC_ROLLRATE_K _ (MC_ROLLRATE_P _ error - -- MC_ROLLRATE_I \* error_integral -- MC_ROLLRATE_D \* error_derivative) - Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. - Set MC_ROLLRATE_K=1 to implement a PID in the parallel form. +Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K _ (MC_ROLLRATE_P _ error + MC_ROLLRATE_I _ error_integral + MC_ROLLRATE_D _ error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -27029,7 +24606,7 @@ Yaw rate differential gain. Small values help reduce fast oscillations. If value | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.0005 | 0.0 | +|   | 0.0 | | 0.01 | 0.0 | ### MC_YAWRATE_FF (`FLOAT`) {#MC_YAWRATE_FF} @@ -27039,7 +24616,7 @@ Improves tracking performance. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.0 | +|   | 0.0 | | 0.01 | 0.0 | ### MC_YAWRATE_I (`FLOAT`) {#MC_YAWRATE_I} @@ -27055,18 +24632,11 @@ Yaw rate integral gain. Can be set to compensate static thrust difference or gra Yaw rate controller gain. -Global gain of the controller. -This gain scales the P, I and D terms of the controller: -output = MC_YAWRATE_K _ (MC_YAWRATE_P _ error - -- MC_YAWRATE_I \* error_integral -- MC_YAWRATE_D \* error_derivative) - Set MC_YAWRATE_P=1 to implement a PID in the ideal form. - Set MC_YAWRATE_K=1 to implement a PID in the parallel form. +Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K _ (MC_YAWRATE_P _ error + MC_YAWRATE_I _ error_integral + MC_YAWRATE_D _ error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 5.0 | 0.0005 | 1.0 | +|   | 0.0 | 5.0 | 0.0005 | 1.0 | ### MC_YAWRATE_P (`FLOAT`) {#MC_YAWRATE_P} @@ -27082,8 +24652,7 @@ Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. Low pass filter cutoff frequency for yaw torque setpoint. -Reduces vibrations by lowering high frequency torque caused by rotor acceleration. -0 disables the filter +Reduces vibrations by lowering high frequency torque caused by rotor acceleration. 0 disables the filter | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -27099,48 +24668,6 @@ Can be set to increase the amount of integrator available to counteract disturba | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.0 | | 0.01 | 0.30 | -## Neural Control - -### MC_NN_EN (`INT32`) {#MC_NN_EN} - -If true the neural network control is automatically started on boot. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | - -### MC_NN_MANL_CTRL (`INT32`) {#MC_NN_MANL_CTRL} - -Enable or disable setting the trajectory setpoint with manual control. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | - -### MC_NN_MAX_RPM (`INT32`) {#MC_NN_MAX_RPM} - -The maximum RPM of the motors. Used to normalize the output of the neural network. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 80000 | | 22000 | - -### MC_NN_MIN_RPM (`INT32`) {#MC_NN_MIN_RPM} - -The minimum RPM of the motors. Used to normalize the output of the neural network. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 80000 | | 1000 | - -### MC_NN_THRST_COEF (`FLOAT`) {#MC_NN_THRST_COEF} - -Thrust coefficient of the motors. Used to normalize the output of the neural network. Divided by 100 000. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 5.0 | | 1.2 | - ## OSD ### MSP_OSD_CONFIG (`INT32`) {#MSP_OSD_CONFIG} @@ -27172,8 +24699,7 @@ Configure on which serial port to run MSP OSD. Enable/Disable the ATXXX OSD Chip. -Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and -select the transmission standard. +Configure the ATXXXX OSD Chip (mounted on the OmnibusF4SD board) and select the transmission standard. **Values:** @@ -27189,9 +24715,7 @@ select the transmission standard. OSD Crosshairs Height. -Controls the vertical position of the crosshair display. -Resolution is limited by OSD to 15 discrete values. Negative -values will display the crosshairs below the horizon +Controls the vertical position of the crosshair display. Resolution is limited by OSD to 15 discrete values. Negative values will display the crosshairs below the horizon | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -27217,22 +24741,11 @@ Minimum security of log level to display on the OSD. | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 3 | -### OSD_RC_STICK (`INT32`) {#OSD_RC_STICK} - -OSD RC Stick commands. - -Forward RC stick input to VTX when disarmed - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 1 | - ### OSD_SCROLL_RATE (`INT32`) {#OSD_SCROLL_RATE} OSD Scroll Rate (ms). -Scroll rate in milliseconds for OSD messages longer than available character width. -This is lower-bounded by the nominal loop rate of this module. +Scroll rate in milliseconds for OSD messages longer than available character width. This is lower-bounded by the nominal loop rate of this module. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -27289,11 +24802,7 @@ Set to 1 to enable S.BUS version 1 output instead of RSSI. Thrust to motor control signal model parameter. -Parameter used to model the nonlinear relationship between -motor control signal (e.g. PWM) and static thrust. -The model is: rel_thrust = factor _ rel_signal^2 + (1-factor) _ rel_signal, -where rel_thrust is the normalized thrust between 0 and 1, and -rel_signal is the relative motor control signal between 0 and 1. +Parameter used to model the nonlinear relationship between motor control signal (e.g. PWM) and static thrust. The model is: rel_thrust = factor _ rel_signal^2 + (1-factor) _ rel_signal, where rel_thrust is the normalized thrust between 0 and 1, and rel_signal is the relative motor control signal between 0 and 1. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -27301,18 +24810,23 @@ rel_signal is the relative motor control signal between 0 and 1. ## Payload Deliverer +### PD_GRIPPER_EN (`INT32`) {#PD_GRIPPER_EN} + +Enable Gripper actuation in Payload Deliverer. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + ### PD_GRIPPER_TO (`FLOAT`) {#PD_GRIPPER_TO} Timeout for successful gripper actuation acknowledgement. -Maximum time Gripper will wait while the successful griper actuation isn't recognised. -If the gripper has no feedback sensor, it will simply wait for -this time before considering gripper actuation successful and publish a -'VehicleCommandAck' signaling successful gripper action +Maximum time Gripper will wait while the successful griper actuation isn't recognised. If the gripper has no feedback sensor, it will simply wait for this time before considering gripper actuation successful and publish a 'VehicleCommandAck' signaling successful gripper action | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | | | 1 | s | +|   | 0 | | | 3 | s | ### PD_GRIPPER_TYPE (`INT32`) {#PD_GRIPPER_TYPE} @@ -27465,6 +24979,16 @@ Select your RC input protocol or auto to scan. ## Radio Calibration +### RC10_DZ (`FLOAT`) {#RC10_DZ} + +RC channel 10 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC10_MAX (`FLOAT`) {#RC10_MAX} RC channel 10 maximum. @@ -27510,6 +25034,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC11_DZ (`FLOAT`) {#RC11_DZ} + +RC channel 11 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC11_MAX (`FLOAT`) {#RC11_MAX} RC channel 11 maximum. @@ -27555,6 +25089,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC12_DZ (`FLOAT`) {#RC12_DZ} + +RC channel 12 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC12_MAX (`FLOAT`) {#RC12_MAX} RC channel 12 maximum. @@ -27600,6 +25144,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC13_DZ (`FLOAT`) {#RC13_DZ} + +RC channel 13 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC13_MAX (`FLOAT`) {#RC13_MAX} RC channel 13 maximum. @@ -27645,6 +25199,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC14_DZ (`FLOAT`) {#RC14_DZ} + +RC channel 14 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC14_MAX (`FLOAT`) {#RC14_MAX} RC channel 14 maximum. @@ -27690,6 +25254,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC15_DZ (`FLOAT`) {#RC15_DZ} + +RC channel 15 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC15_MAX (`FLOAT`) {#RC15_MAX} RC channel 15 maximum. @@ -27735,6 +25309,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC16_DZ (`FLOAT`) {#RC16_DZ} + +RC channel 16 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC16_MAX (`FLOAT`) {#RC16_MAX} RC channel 16 maximum. @@ -27780,6 +25364,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC17_DZ (`FLOAT`) {#RC17_DZ} + +RC channel 17 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC17_MAX (`FLOAT`) {#RC17_MAX} RC channel 17 maximum. @@ -27825,6 +25419,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC18_DZ (`FLOAT`) {#RC18_DZ} + +RC channel 18 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 0.0 | + ### RC18_MAX (`FLOAT`) {#RC18_MAX} RC channel 18 maximum. @@ -27870,6 +25474,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | +### RC1_DZ (`FLOAT`) {#RC1_DZ} + +RC channel 1 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 10.0 | us | + ### RC1_MAX (`FLOAT`) {#RC1_MAX} RC channel 1 maximum. @@ -27915,6 +25529,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500.0 | us | +### RC2_DZ (`FLOAT`) {#RC2_DZ} + +RC channel 2 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 10.0 | us | + ### RC2_MAX (`FLOAT`) {#RC2_MAX} RC channel 2 maximum. @@ -27960,6 +25584,16 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500.0 | us | +### RC3_DZ (`FLOAT`) {#RC3_DZ} + +RC channel 3 dead zone. + +The +- range of this value around the trim value will be considered as zero. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 100.0 | | 10.0 | us | + ### RC3_MAX (`FLOAT`) {#RC3_MAX} RC channel 3 maximum. @@ -28005,953 +25639,359 @@ Mid point value | ------ | -------- | -------- | --------- | ------- | ---- | |   | 800.0 | 2200.0 | | 1500 | us | -### RC4_MAX (`FLOAT`) {#RC4_MAX} - -RC channel 4 maximum. - -Maximum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1500.0 | 2200.0 | | 2000 | us | - -### RC4_MIN (`FLOAT`) {#RC4_MIN} - -RC channel 4 minimum. - -Minimum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 1500.0 | | 1000 | us | - -### RC4_REV (`FLOAT`) {#RC4_REV} - -RC channel 4 reverse. - -Set to -1 to reverse channel. - -**Values:** - -- `-1.0`: Reverse -- `1.0`: Normal - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1.0 | 1.0 | | 1.0 | - -### RC4_TRIM (`FLOAT`) {#RC4_TRIM} - -RC channel 4 trim. - -Mid point value - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 2200.0 | | 1500 | us | - -### RC5_MAX (`FLOAT`) {#RC5_MAX} - -RC channel 5 maximum. - -Maximum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1500.0 | 2200.0 | | 2000 | us | - -### RC5_MIN (`FLOAT`) {#RC5_MIN} - -RC channel 5 minimum. - -Minimum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 1500.0 | | 1000 | us | - -### RC5_REV (`FLOAT`) {#RC5_REV} - -RC channel 5 reverse. - -Set to -1 to reverse channel. - -**Values:** - -- `-1.0`: Reverse -- `1.0`: Normal - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1.0 | 1.0 | | 1.0 | - -### RC5_TRIM (`FLOAT`) {#RC5_TRIM} - -RC channel 5 trim. - -Mid point value - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 2200.0 | | 1500 | us | - -### RC6_MAX (`FLOAT`) {#RC6_MAX} - -RC channel 6 maximum. - -Maximum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1500.0 | 2200.0 | | 2000 | us | - -### RC6_MIN (`FLOAT`) {#RC6_MIN} - -RC channel 6 minimum. - -Minimum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 1500.0 | | 1000 | us | - -### RC6_REV (`FLOAT`) {#RC6_REV} - -RC channel 6 reverse. - -Set to -1 to reverse channel. - -**Values:** - -- `-1.0`: Reverse -- `1.0`: Normal - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1.0 | 1.0 | | 1.0 | - -### RC6_TRIM (`FLOAT`) {#RC6_TRIM} - -RC channel 6 trim. - -Mid point value - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 2200.0 | | 1500 | us | - -### RC7_MAX (`FLOAT`) {#RC7_MAX} - -RC channel 7 maximum. - -Maximum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1500.0 | 2200.0 | | 2000 | us | - -### RC7_MIN (`FLOAT`) {#RC7_MIN} - -RC channel 7 minimum. - -Minimum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 1500.0 | | 1000 | us | - -### RC7_REV (`FLOAT`) {#RC7_REV} - -RC channel 7 reverse. - -Set to -1 to reverse channel. - -**Values:** - -- `-1.0`: Reverse -- `1.0`: Normal - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1.0 | 1.0 | | 1.0 | - -### RC7_TRIM (`FLOAT`) {#RC7_TRIM} - -RC channel 7 trim. - -Mid point value - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 2200.0 | | 1500 | us | - -### RC8_MAX (`FLOAT`) {#RC8_MAX} - -RC channel 8 maximum. - -Maximum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1500.0 | 2200.0 | | 2000 | us | - -### RC8_MIN (`FLOAT`) {#RC8_MIN} - -RC channel 8 minimum. - -Minimum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 1500.0 | | 1000 | us | - -### RC8_REV (`FLOAT`) {#RC8_REV} - -RC channel 8 reverse. - -Set to -1 to reverse channel. - -**Values:** - -- `-1.0`: Reverse -- `1.0`: Normal - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1.0 | 1.0 | | 1.0 | - -### RC8_TRIM (`FLOAT`) {#RC8_TRIM} - -RC channel 8 trim. - -Mid point value - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 2200.0 | | 1500 | us | - -### RC9_MAX (`FLOAT`) {#RC9_MAX} - -RC channel 9 maximum. - -Maximum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1500.0 | 2200.0 | | 2000 | us | - -### RC9_MIN (`FLOAT`) {#RC9_MIN} - -RC channel 9 minimum. - -Minimum value for this channel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 1500.0 | | 1000 | us | - -### RC9_REV (`FLOAT`) {#RC9_REV} - -RC channel 9 reverse. - -Set to -1 to reverse channel. - -**Values:** - -- `-1.0`: Reverse -- `1.0`: Normal - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1.0 | 1.0 | | 1.0 | - -### RC9_TRIM (`FLOAT`) {#RC9_TRIM} - -RC channel 9 trim. - -Mid point value - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 800.0 | 2200.0 | | 1500 | us | - -### RC_CHAN_CNT (`INT32`) {#RC_CHAN_CNT} - -RC channel count. - -This parameter is used by Ground Station software to save the number -of channels which were used during RC calibration. It is only meant -for ground station use. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | - -### RC_FAILS_THR (`INT32`) {#RC_FAILS_THR} - -Failsafe channel PWM threshold. - -Use RC_MAP_FAILSAFE to specify which channel is used to indicate RC loss via this threshold. -By default this is the throttle channel. -Set to a PWM value slightly above the PWM value for the channel (e.g. throttle) in a failsafe event, -but below the minimum PWM value for the channel during normal operation. -Note: The default value of 0 disables the feature (it is below the expected range). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 2200 | | 0 | us | - -### RC_MAP_AUX1 (`INT32`) {#RC_MAP_AUX1} - -AUX1 Passthrough RC channel. - -**Values:** - -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | - -### RC_MAP_AUX2 (`INT32`) {#RC_MAP_AUX2} - -AUX2 Passthrough RC channel. - -**Values:** - -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | - -### RC_MAP_AUX3 (`INT32`) {#RC_MAP_AUX3} - -AUX3 Passthrough RC channel. +### RC4_DZ (`FLOAT`) {#RC4_DZ} -**Values:** +RC channel 4 dead zone. -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +The +- range of this value around the trim value will be considered as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | - -### RC_MAP_AUX4 (`INT32`) {#RC_MAP_AUX4} - -AUX4 Passthrough RC channel. - -**Values:** - -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +|   | 0.0 | 100.0 | | 10.0 | us | + +### RC4_MAX (`FLOAT`) {#RC4_MAX} + +RC channel 4 maximum. + +Maximum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | - -### RC_MAP_AUX5 (`INT32`) {#RC_MAP_AUX5} +|   | 1500.0 | 2200.0 | | 2000 | us | -AUX5 Passthrough RC channel. +### RC4_MIN (`FLOAT`) {#RC4_MIN} -**Values:** +RC channel 4 minimum. -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +Minimum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 800.0 | 1500.0 | | 1000 | us | -### RC_MAP_AUX6 (`INT32`) {#RC_MAP_AUX6} +### RC4_REV (`FLOAT`) {#RC4_REV} -AUX6 Passthrough RC channel. +RC channel 4 reverse. + +Set to -1 to reverse channel. **Values:** -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +- `-1.0`: Reverse +- `1.0`: Normal | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | -1.0 | 1.0 | | 1.0 | -### RC_MAP_ENG_MOT (`INT32`) {#RC_MAP_ENG_MOT} +### RC4_TRIM (`FLOAT`) {#RC4_TRIM} -RC channel to engage the main motor (for helicopters). +RC channel 4 trim. -**Values:** +Mid point value -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 800.0 | 2200.0 | | 1500 | us | + +### RC5_DZ (`FLOAT`) {#RC5_DZ} + +RC channel 5 dead zone. + +The +- range of this value around the trim value will be considered as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 0.0 | 100.0 | | 10.0 | -### RC_MAP_FAILSAFE (`INT32`) {#RC_MAP_FAILSAFE} +### RC5_MAX (`FLOAT`) {#RC5_MAX} -Failsafe channel mapping. +RC channel 5 maximum. -Configures which RC channel is used by the receiver to indicate the signal was lost -(on receivers that use output a fixed signal value to report lost signal). -If set to 0, the channel mapped to throttle is used. -Use RC_FAILS_THR to set the threshold indicating lost signal. By default it's below -the expected range and hence disabled. +Maximum value for this channel. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1500.0 | 2200.0 | | 2000 | us | -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +### RC5_MIN (`FLOAT`) {#RC5_MIN} + +RC channel 5 minimum. + +Minimum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 800.0 | 1500.0 | | 1000 | us | -### RC_MAP_PARAM1 (`INT32`) {#RC_MAP_PARAM1} +### RC5_REV (`FLOAT`) {#RC5_REV} -PARAM1 tuning channel. +RC channel 5 reverse. -Can be used for parameter tuning with the RC. This one is further referenced as the 1st parameter channel. -Set to 0 to deactivate \* +Set to -1 to reverse channel. **Values:** -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +- `-1.0`: Reverse +- `1.0`: Normal | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | -1.0 | 1.0 | | 1.0 | -### RC_MAP_PARAM2 (`INT32`) {#RC_MAP_PARAM2} +### RC5_TRIM (`FLOAT`) {#RC5_TRIM} -PARAM2 tuning channel. +RC channel 5 trim. -Can be used for parameter tuning with the RC. This one is further referenced as the 2nd parameter channel. -Set to 0 to deactivate \* +Mid point value -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 800.0 | 2200.0 | | 1500 | us | -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +### RC6_DZ (`FLOAT`) {#RC6_DZ} + +RC channel 6 dead zone. + +The +- range of this value around the trim value will be considered as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 0.0 | 100.0 | | 10.0 | -### RC_MAP_PARAM3 (`INT32`) {#RC_MAP_PARAM3} +### RC6_MAX (`FLOAT`) {#RC6_MAX} -PARAM3 tuning channel. +RC channel 6 maximum. -Can be used for parameter tuning with the RC. This one is further referenced as the 3th parameter channel. -Set to 0 to deactivate \* +Maximum value for this channel. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1500.0 | 2200.0 | | 2000 | us | -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +### RC6_MIN (`FLOAT`) {#RC6_MIN} + +RC channel 6 minimum. + +Minimum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 800.0 | 1500.0 | | 1000 | us | -### RC_MAP_PITCH (`INT32`) {#RC_MAP_PITCH} +### RC6_REV (`FLOAT`) {#RC6_REV} -Pitch control channel mapping. +RC channel 6 reverse. -The channel index (starting from 1 for channel 1) indicates -which channel should be used for reading pitch inputs from. -A value of zero indicates the switch is not assigned. +Set to -1 to reverse channel. **Values:** -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +- `-1.0`: Reverse +- `1.0`: Normal | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | -1.0 | 1.0 | | 1.0 | -### RC_MAP_ROLL (`INT32`) {#RC_MAP_ROLL} +### RC6_TRIM (`FLOAT`) {#RC6_TRIM} -Roll control channel mapping. +RC channel 6 trim. -The channel index (starting from 1 for channel 1) indicates -which channel should be used for reading roll inputs from. -A value of zero indicates the switch is not assigned. +Mid point value -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 800.0 | 2200.0 | | 1500 | us | -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +### RC7_DZ (`FLOAT`) {#RC7_DZ} + +RC channel 7 dead zone. + +The +- range of this value around the trim value will be considered as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 0.0 | 100.0 | | 10.0 | -### RC_MAP_THROTTLE (`INT32`) {#RC_MAP_THROTTLE} +### RC7_MAX (`FLOAT`) {#RC7_MAX} -Throttle control channel mapping. +RC channel 7 maximum. -The channel index (starting from 1 for channel 1) indicates -which channel should be used for reading throttle inputs from. -A value of zero indicates the switch is not assigned. +Maximum value for this channel. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1500.0 | 2200.0 | | 2000 | us | -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +### RC7_MIN (`FLOAT`) {#RC7_MIN} + +RC channel 7 minimum. + +Minimum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 800.0 | 1500.0 | | 1000 | us | -### RC_MAP_YAW (`INT32`) {#RC_MAP_YAW} +### RC7_REV (`FLOAT`) {#RC7_REV} -Yaw control channel mapping. +RC channel 7 reverse. -The channel index (starting from 1 for channel 1) indicates -which channel should be used for reading yaw inputs from. -A value of zero indicates the switch is not assigned. +Set to -1 to reverse channel. **Values:** -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +- `-1.0`: Reverse +- `1.0`: Normal | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | -1.0 | 1.0 | | 1.0 | -### RC_RSSI_PWM_CHAN (`INT32`) {#RC_RSSI_PWM_CHAN} +### RC7_TRIM (`FLOAT`) {#RC7_TRIM} -PWM input channel that provides RSSI. +RC channel 7 trim. -0: do not read RSSI from input channel -1-18: read RSSI from specified input channel -Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. +Mid point value -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 800.0 | 2200.0 | | 1500 | us | -- `0`: Unassigned -- `1`: Channel 1 -- `2`: Channel 2 -- `3`: Channel 3 -- `4`: Channel 4 -- `5`: Channel 5 -- `6`: Channel 6 -- `7`: Channel 7 -- `8`: Channel 8 -- `9`: Channel 9 -- `10`: Channel 10 -- `11`: Channel 11 -- `12`: Channel 12 -- `13`: Channel 13 -- `14`: Channel 14 -- `15`: Channel 15 -- `16`: Channel 16 -- `17`: Channel 17 -- `18`: Channel 18 +### RC8_DZ (`FLOAT`) {#RC8_DZ} + +RC channel 8 dead zone. + +The +- range of this value around the trim value will be considered as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 18 | | 0 | +|   | 0.0 | 100.0 | | 10.0 | -### RC_RSSI_PWM_MAX (`INT32`) {#RC_RSSI_PWM_MAX} +### RC8_MAX (`FLOAT`) {#RC8_MAX} -Max input value for RSSI reading. +RC channel 8 maximum. -Only used if RC_RSSI_PWM_CHAN > 0 +Maximum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 2000 | | 2000 | +|   | 1500.0 | 2200.0 | | 2000 | us | -### RC_RSSI_PWM_MIN (`INT32`) {#RC_RSSI_PWM_MIN} +### RC8_MIN (`FLOAT`) {#RC8_MIN} -Min input value for RSSI reading. +RC channel 8 minimum. -Only used if RC_RSSI_PWM_CHAN > 0 +Minimum value for this channel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 2000 | | 1000 | +|   | 800.0 | 1500.0 | | 1000 | us | -### TRIM_PITCH (`FLOAT`) {#TRIM_PITCH} +### RC8_REV (`FLOAT`) {#RC8_REV} -Pitch trim. +RC channel 8 reverse. + +Set to -1 to reverse channel. + +**Values:** -The trim value is the actuator control value the system needs -for straight and level flight. +- `-1.0`: Reverse +- `1.0`: Normal | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -0.5 | 0.5 | 0.01 | 0.0 | +|   | -1.0 | 1.0 | | 1.0 | -### TRIM_ROLL (`FLOAT`) {#TRIM_ROLL} +### RC8_TRIM (`FLOAT`) {#RC8_TRIM} -Roll trim. +RC channel 8 trim. -The trim value is the actuator control value the system needs -for straight and level flight. +Mid point value | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -0.5 | 0.5 | 0.01 | 0.0 | +|   | 800.0 | 2200.0 | | 1500 | us | -### TRIM_YAW (`FLOAT`) {#TRIM_YAW} +### RC9_DZ (`FLOAT`) {#RC9_DZ} -Yaw trim. +RC channel 9 dead zone. -The trim value is the actuator control value the system needs -for straight and level flight. +The +- range of this value around the trim value will be considered as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -0.5 | 0.5 | 0.01 | 0.0 | - -## Radio Switches +|   | 0.0 | 100.0 | | 0.0 | -### RC_ARMSWITCH_TH (`FLOAT`) {#RC_ARMSWITCH_TH} +### RC9_MAX (`FLOAT`) {#RC9_MAX} -Threshold for the arm switch. +RC channel 9 maximum. -0-1 indicate where in the full channel range the threshold sits -0 : min -1 : max -sign indicates polarity of comparison -positive : true when channel>th -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channelth -negative : true when channel The rover starts to cut the corner earlier. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 100 | 0.01 | 1 | - -### RA_ACC_RAD_MAX (`FLOAT`) {#RA_ACC_RAD_MAX} - -Maximum acceptance radius for the waypoints. - -The controller scales the acceptance radius based on the angle between -the previous, current and next waypoint. -Higher value -> smoother trajectory at the cost of how close the rover gets -to the waypoint (Set to -1 to disable corner cutting). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | 0.01 | -1 | m | - -### RA_MAX_STR_ANG (`FLOAT`) {#RA_MAX_STR_ANG} - -Maximum steering angle. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1.5708 | 0.01 | 0 | rad | - -### RA_STR_RATE_LIM (`FLOAT`) {#RA_STR_RATE_LIM} - -Steering rate limit. - -Set to -1 to disable. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | -1 | 1000 | 0.01 | -1 | deg/s | - -### RA_WHEEL_BASE (`FLOAT`) {#RA_WHEEL_BASE} - -Wheel base. - -Distance from the front to the rear axle. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.001 | 0 | m | - -## Rover Attitude Control - -### RO_YAW_P (`FLOAT`) {#RO_YAW_P} - -Proportional gain for closed loop yaw controller. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.01 | 0. | - -## Rover Differential - -### RD_TRANS_DRV_TRN (`FLOAT`) {#RD_TRANS_DRV_TRN} - -Yaw error threshhold to switch from driving to spot turning. - -This threshold is used for the state machine to switch from driving to turning based on the -error between the desired and actual yaw. It is also used as the threshold whether the rover should come -to a smooth stop at the next waypoint. This slow down effect is active if the angle between the -line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | -------- | ---- | -|   | 0.001 | 3.14159 | 0.01 | 0.174533 | rad | - -### RD_TRANS_TRN_DRV (`FLOAT`) {#RD_TRANS_TRN_DRV} - -Yaw error threshhold to switch from spot turning to driving. - -This threshold is used for the state machine to switch from turning to driving based on the -error between the desired and actual yaw. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | --------- | ---- | -|   | 0.001 | 3.14159 | 0.01 | 0.0872665 | rad | - -### RD_WHEEL_TRACK (`FLOAT`) {#RD_WHEEL_TRACK} - -Wheel track. - -Distance from the center of the right wheel to the center of the left wheel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.001 | 0 | m | - -### RD_YAW_STK_GAIN (`FLOAT`) {#RD_YAW_STK_GAIN} - -Yaw stick gain for Manual mode. - -Assign value <1.0 to decrease stick response for yaw control. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 1 | 0.01 | 1 | - -## Rover Mecanum - -### RM_COURSE_CTL_TH (`FLOAT`) {#RM_COURSE_CTL_TH} - -Threshold to update course control in manual position mode. - -Threshold for the angle between the active cruise direction and the cruise direction given -by the stick inputs. -This can be understood as a deadzone for the combined stick inputs for forward/backwards -and lateral speed which defines a course direction. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 3.14 | 0.01 | 0.17 | rad | - -### RM_WHEEL_TRACK (`FLOAT`) {#RM_WHEEL_TRACK} - -Wheel track. - -Distance from the center of the right wheel to the center of the left wheel. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.001 | 0 | m | - -### RM_YAW_STK_GAIN (`FLOAT`) {#RM_YAW_STK_GAIN} - -Yaw stick gain for Manual mode. - -Assign value <1.0 to decrease stick response for yaw control. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 1 | 0.01 | 1 | - -## Rover Rate Control - -### RO_YAW_ACCEL_LIM (`FLOAT`) {#RO_YAW_ACCEL_LIM} - -Yaw acceleration limit. - -Used to cap how quickly the magnitude of yaw rate setpoints can increase. -Set to -1 to disable. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------- | -|   | -1 | 10000 | 0.01 | -1. | deg/s^2 | - -### RO_YAW_DECEL_LIM (`FLOAT`) {#RO_YAW_DECEL_LIM} - -Yaw deceleration limit. - -Used to cap how quickly the magnitude of yaw rate setpoints can decrease. -Set to -1 to disable. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------- | -|   | -1 | 10000 | 0.01 | -1. | deg/s^2 | - -### RO_YAW_EXPO (`FLOAT`) {#RO_YAW_EXPO} - -Yaw rate expo factor. - -Exponential factor for tuning the input curve shape. -0 Purely linear input curve -1 Purely cubic input curve - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 0. | - -### RO_YAW_RATE_CORR (`FLOAT`) {#RO_YAW_RATE_CORR} - -Yaw rate correction factor. - -Multiplicative correction factor for the feedforward mapping of the yaw rate controller. -Increase this value (x > 1) if the measured yaw rate is lower than the setpoint, decrease (0 < x < 1) otherwise. -Note: Tuning this is particularly useful for skid-steered rovers, or rovers with misaligned wheels/steering axes -that cause a lot of friction when turning. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 10000 | 0.01 | 1. | - -### RO_YAW_RATE_I (`FLOAT`) {#RO_YAW_RATE_I} - -Integral gain for closed loop yaw rate controller. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.01 | 0. | - -### RO_YAW_RATE_LIM (`FLOAT`) {#RO_YAW_RATE_LIM} - -Yaw rate limit. - -Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints -in Acro, Stabilized and Position mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0 | 10000 | 0.01 | 0. | deg/s | - -### RO_YAW_RATE_P (`FLOAT`) {#RO_YAW_RATE_P} - -Proportional gain for closed loop yaw rate controller. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.01 | 0. | - -### RO_YAW_RATE_TH (`FLOAT`) {#RO_YAW_RATE_TH} - -Yaw rate measurement threshold. - -The minimum threshold for the yaw rate measurement not to be interpreted as zero. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0 | 100 | 0.01 | 3. | deg/s | - -### RO_YAW_STICK_DZ (`FLOAT`) {#RO_YAW_STICK_DZ} - -Yaw stick deadzone. - -Percentage of stick input range that will be interpreted as zero around the stick centered value. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.01 | 0.1 | - -### RO_YAW_SUPEXPO (`FLOAT`) {#RO_YAW_SUPEXPO} - -Yaw rate super expo factor. - -"Superexponential" factor for refining the input curve shape tuned using RO_YAW_EXPO. -0 Pure Expo function -0.7 reasonable shape enhancement for intuitive stick feel -0.95 very strong bent input curve only near maxima have effect +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 0.95 | | 0. | - -## Rover Velocity Control - -### RO_ACCEL_LIM (`FLOAT`) {#RO_ACCEL_LIM} - -Acceleration limit. - -Set to -1 to disable. -For mecanum rovers this limit is used for longitudinal and lateral acceleration. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | -1 | 100 | 0.01 | -1. | m/s^2 | +|   | 0 | 18 | | 0 | -### RO_DECEL_LIM (`FLOAT`) {#RO_DECEL_LIM} +### RC_MAP_YAW (`INT32`) {#RC_MAP_YAW} -Deceleration limit. +Yaw control channel mapping. -Set to -1 to disable. -Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. -For mecanum rovers this limit is used for longitudinal and lateral deceleration. +The channel index (starting from 1 for channel 1) indicates which channel should be used for reading yaw inputs from. A value of zero indicates the switch is not assigned. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | -1 | 100 | 0.01 | -1. | m/s^2 | +**Values:** -### RO_JERK_LIM (`FLOAT`) {#RO_JERK_LIM} +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 -Jerk limit. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 18 | | 0 | -Set to -1 to disable. -Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. -For mecanum rovers this limit is used for longitudinal and lateral jerk. +### RC_RSSI_PWM_CHAN (`INT32`) {#RC_RSSI_PWM_CHAN} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | -1 | 100 | 0.01 | -1. | m/s^3 | +PWM input channel that provides RSSI. -### RO_MAX_THR_SPEED (`FLOAT`) {#RO_MAX_THR_SPEED} +0: do not read RSSI from input channel 1-18: read RSSI from specified input channel Specify the range for RSSI input with RC_RSSI_PWM_MIN and RC_RSSI_PWM_MAX parameters. -Speed the rover drives at maximum throttle. +**Values:** -Used to linearly map speeds [m/s] to throttle values [-1. 1]. +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.01 | 0. | m/s | +|   | 0 | 18 | | 0 | -### RO_SPEED_I (`FLOAT`) {#RO_SPEED_I} +### RC_RSSI_PWM_MAX (`INT32`) {#RC_RSSI_PWM_MAX} -Integral gain for ground speed controller. +Max input value for RSSI reading. + +Only used if RC_RSSI_PWM_CHAN > 0 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.001 | 0. | +|   | 0 | 2000 | | 2000 | -### RO_SPEED_LIM (`FLOAT`) {#RO_SPEED_LIM} +### RC_RSSI_PWM_MIN (`INT32`) {#RC_RSSI_PWM_MIN} -Speed limit. +Min input value for RSSI reading. -Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode. +Only used if RC_RSSI_PWM_CHAN > 0 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | 0.01 | -1. | m/s | +|   | 0 | 2000 | | 1000 | -### RO_SPEED_P (`FLOAT`) {#RO_SPEED_P} +### TRIM_PITCH (`FLOAT`) {#TRIM_PITCH} -Proportional gain for ground speed controller. +Pitch trim. + +The trim value is the actuator control value the system needs for straight and level flight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.01 | 0. | +|   | -0.5 | 0.5 | 0.01 | 0.0 | -### RO_SPEED_RED (`FLOAT`) {#RO_SPEED_RED} +### TRIM_ROLL (`FLOAT`) {#TRIM_ROLL} -Tuning parameter for the speed reduction based on the course error. +Roll trim. -Reduced_speed = RO_MAX_THR_SPEED _ (1 - normalized_course_error _ RO_SPEED_RED) -The normalized course error is the angle between the current course and the bearing setpoint -interpolated from [0, 180] -> [0, 1]. -Higher value -> More speed reduction. -Note: This is also used to calculate the speed at which the vehicle arrives at a waypoint in auto modes. -Set to -1 to disable bearing error based speed reduction. +The trim value is the actuator control value the system needs for straight and level flight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | 0.01 | -1. | +|   | -0.5 | 0.5 | 0.01 | 0.0 | -### RO_SPEED_TH (`FLOAT`) {#RO_SPEED_TH} +### TRIM_YAW (`FLOAT`) {#TRIM_YAW} -Speed measurement threshold. +Yaw trim. -Set to -1 to disable. -The minimum threshold for the speed measurement not to be interpreted as zero. +The trim value is the actuator control value the system needs for straight and level flight. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 100 | 0.01 | 0.1 | m/s | +|   | -0.5 | 0.5 | 0.01 | 0.0 | -## Runway Takeoff +## Radio Switches -### RWTO_MAX_THR (`FLOAT`) {#RWTO_MAX_THR} +### RC_ARMSWITCH_TH (`FLOAT`) {#RC_ARMSWITCH_TH} -Throttle during runway takeoff. +Threshold for the arm switch. + +0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel30% -- `4`: from 1st armed until shutdown +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 18 | | 0 | -### SDLOG_PROFILE (`INT32`) {#SDLOG_PROFILE} +### RC_MAP_PAY_SW (`INT32`) {#RC_MAP_PAY_SW} -Logging topic profile (integer bitmask). +Payload Power Switch RC channel. -This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug\_\*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging) +**Values:** -**Bitmask:** +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 -- `0`: Default set (general log analysis) -- `1`: Estimator replay (EKF2) -- `2`: Thermal calibration -- `3`: System identification -- `4`: High rate -- `5`: Debug -- `6`: Sensor comparison -- `7`: Computer Vision and Avoidance -- `8`: Raw FIFO high-rate IMU (Gyro) -- `9`: Raw FIFO high-rate IMU (Accel) -- `10`: Mavlink tunnel message logging -- `11`: High rate sensors +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 18 | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 4095 | | 1 | +### RC_MAP_RETURN_SW (`INT32`) {#RC_MAP_RETURN_SW} -### SDLOG_UTC_OFFSET (`INT32`) {#SDLOG_UTC_OFFSET} +Return switch channel. -UTC offset (unit: min). +**Values:** -the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9\*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1000 | 1000 | | 0 | min | - -### SDLOG_UUID (`INT32`) {#SDLOG_UUID} - -Log UUID. - -If set to 1, add an ID to the log, which uniquely identifies the vehicle +|   | 0 | 18 | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +### RC_MAP_TRANS_SW (`INT32`) {#RC_MAP_TRANS_SW} -## SITL +VTOL transition switch channel mapping. -### SIM_BAT_DRAIN (`FLOAT`) {#SIM_BAT_DRAIN} +**Values:** -Simulator Battery drain interval. +- `0`: Unassigned +- `1`: Channel 1 +- `2`: Channel 2 +- `3`: Channel 3 +- `4`: Channel 4 +- `5`: Channel 5 +- `6`: Channel 6 +- `7`: Channel 7 +- `8`: Channel 8 +- `9`: Channel 9 +- `10`: Channel 10 +- `11`: Channel 11 +- `12`: Channel 12 +- `13`: Channel 13 +- `14`: Channel 14 +- `15`: Channel 15 +- `16`: Channel 16 +- `17`: Channel 17 +- `18`: Channel 18 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 86400 | 1 | 60 | s | +|   | 0 | 18 | | 0 | -### SIM_BAT_ENABLE (`INT32`) {#SIM_BAT_ENABLE} +### RC_OFFB_TH (`FLOAT`) {#RC_OFFB_TH} -Simulator Battery enabled. +Threshold for selecting offboard mode. -Enable or disable the internal battery simulation. This is useful -when the battery is simulated externally and interfaced with PX4 -through MAVLink for example. +0-1 indicate where in the full channel range the threshold sits 0 : min 1 : max sign indicates polarity of comparison positive : true when channel>th negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel The rover starts to cut the corner earlier. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +|   | 1 | 100 | 0.01 | 1 | -### CAL_ACC2_YOFF (`FLOAT`) {#CAL_ACC2_YOFF} +### RA_ACC_RAD_MAX (`FLOAT`) {#RA_ACC_RAD_MAX} -Accelerometer 2 Y-axis offset. +Maximum acceptance radius for the waypoints. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | m/s^2 | +The controller scales the acceptance radius based on the angle between the previous, current and next waypoint. Higher value -> smoother trajectory at the cost of how close the rover gets to the waypoint (Set to -1 to disable corner cutting). -### CAL_ACC2_YSCALE (`FLOAT`) {#CAL_ACC2_YSCALE} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 100 | 0.01 | -1 | m | -Accelerometer 2 Y-axis scaling factor. +### RA_MAX_STR_ANG (`FLOAT`) {#RA_MAX_STR_ANG} + +Maximum steering angle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +|   | 0 | 1.5708 | 0.01 | 0 | rad | -### CAL_ACC2_ZOFF (`FLOAT`) {#CAL_ACC2_ZOFF} +### RA_STR_RATE_LIM (`FLOAT`) {#RA_STR_RATE_LIM} -Accelerometer 2 Z-axis offset. +Steering rate limit. + +Set to -1 to disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | m/s^2 | +|   | -1 | 1000 | 0.01 | -1 | deg/s | -### CAL_ACC2_ZSCALE (`FLOAT`) {#CAL_ACC2_ZSCALE} +### RA_WHEEL_BASE (`FLOAT`) {#RA_WHEEL_BASE} -Accelerometer 2 Z-axis scaling factor. +Wheel base. + +Distance from the front to the rear axle. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +|   | 0 | 100 | 0.001 | 0 | m | -### CAL_ACC3_ID (`INT32`) {#CAL_ACC3_ID} +## Rover Attitude Control -Accelerometer 3 calibration device ID. +### RO_YAW_P (`FLOAT`) {#RO_YAW_P} -Device ID of the accelerometer this calibration applies to. +Proportional gain for closed loop yaw controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0 | 100 | 0.01 | 0. | -### CAL_ACC3_PRIO (`INT32`) {#CAL_ACC3_PRIO} +## Rover Differential -Accelerometer 3 priority. +### RD_MAX_THR_YAW_R (`FLOAT`) {#RD_MAX_THR_YAW_R} -**Values:** +Yaw rate turning left/right wheels at max speed in opposite directions. -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | - -### CAL_ACC3_ROT (`INT32`) {#CAL_ACC3_ROT} - -Accelerometer 3 rotation relative to airframe. +|   | 0 | 100 | 0.01 | 0 | m/s | -An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. +### RD_MISS_SPD_GAIN (`FLOAT`) {#RD_MISS_SPD_GAIN} -**Values:** +Tuning parameter for the speed reduction during waypoint transition. -- `-1`: Internal -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° -- `8`: Roll 180° -- `9`: Roll 180°, Yaw 45° -- `10`: Roll 180°, Yaw 90° -- `11`: Roll 180°, Yaw 135° -- `12`: Pitch 180° -- `13`: Roll 180°, Yaw 225° -- `14`: Roll 180°, Yaw 270° -- `15`: Roll 180°, Yaw 315° -- `16`: Roll 90° -- `17`: Roll 90°, Yaw 45° -- `18`: Roll 90°, Yaw 90° -- `19`: Roll 90°, Yaw 135° -- `20`: Roll 270° -- `21`: Roll 270°, Yaw 45° -- `22`: Roll 270°, Yaw 90° -- `23`: Roll 270°, Yaw 135° -- `24`: Pitch 90° -- `25`: Pitch 270° -- `26`: Pitch 180°, Yaw 90° -- `27`: Pitch 180°, Yaw 270° -- `28`: Roll 90°, Pitch 90° -- `29`: Roll 180°, Pitch 90° -- `30`: Roll 270°, Pitch 90° -- `31`: Roll 90°, Pitch 180° -- `32`: Roll 270°, Pitch 180° -- `33`: Roll 90°, Pitch 270° -- `34`: Roll 180°, Pitch 270° -- `35`: Roll 270°, Pitch 270° -- `36`: Roll 90°, Pitch 180°, Yaw 90° -- `37`: Roll 90°, Yaw 270° -- `38`: Roll 90°, Pitch 68°, Yaw 293° -- `39`: Pitch 315° -- `40`: Roll 90°, Pitch 315° +The waypoint transition speed is calculated as: Transition_speed = Maximum_speed _ (1 - normalized_transition_angle _ RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr WP and curr-next WP interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 40 | | -1 | +|   | -1 | 100 | 0.01 | -1 | -### CAL_ACC3_XOFF (`FLOAT`) {#CAL_ACC3_XOFF} +### RD_TRANS_DRV_TRN (`FLOAT`) {#RD_TRANS_DRV_TRN} -Accelerometer 3 X-axis offset. +Yaw error threshhold to switch from driving to spot turning. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | m/s^2 | +This threshold is used for the state machine to switch from driving to turning based on the error between the desired and actual yaw. It is also used as the threshold whether the rover should come to a smooth stop at the next waypoint. This slow down effect is active if the angle between the line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | -------- | ---- | +|   | 0.001 | 3.14159 | 0.01 | 0.174533 | rad | + +### RD_TRANS_TRN_DRV (`FLOAT`) {#RD_TRANS_TRN_DRV} + +Yaw error threshhold to switch from spot turning to driving. + +This threshold is used for the state machine to switch from turning to driving based on the error between the desired and actual yaw. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | --------- | ---- | +|   | 0.001 | 3.14159 | 0.01 | 0.0872665 | rad | + +### RD_WHEEL_TRACK (`FLOAT`) {#RD_WHEEL_TRACK} -### CAL_ACC3_XSCALE (`FLOAT`) {#CAL_ACC3_XSCALE} +Wheel track. -Accelerometer 3 X-axis scaling factor. +Distance from the center of the right wheel to the center of the left wheel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | - -### CAL_ACC3_YOFF (`FLOAT`) {#CAL_ACC3_YOFF} +|   | 0 | 100 | 0.001 | 0 | m | -Accelerometer 3 Y-axis offset. +## Rover Mecanum -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | m/s^2 | +### RM_COURSE_CTL_TH (`FLOAT`) {#RM_COURSE_CTL_TH} -### CAL_ACC3_YSCALE (`FLOAT`) {#CAL_ACC3_YSCALE} +Threshold to update course control in manual position mode. -Accelerometer 3 Y-axis scaling factor. +Threshold for the angle between the active cruise direction and the cruise direction given by the stick inputs. This can be understood as a deadzone for the combined stick inputs for forward/backwards and lateral speed which defines a course direction. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | - -### CAL_ACC3_ZOFF (`FLOAT`) {#CAL_ACC3_ZOFF} - -Accelerometer 3 Z-axis offset. +|   | 0 | 3.14 | 0.01 | 0.17 | rad | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | m/s^2 | +### RM_MAX_THR_YAW_R (`FLOAT`) {#RM_MAX_THR_YAW_R} -### CAL_ACC3_ZSCALE (`FLOAT`) {#CAL_ACC3_ZSCALE} +Yaw rate turning left/right wheels at max speed in opposite directions. -Accelerometer 3 Z-axis scaling factor. +This parameter is used to calculate the feedforward term of the closed loop yaw rate control. The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. This desired speed difference is then linearly mapped to normalized motor commands. A good starting point is half the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +|   | 0 | 100 | 0.01 | 0 | m/s | -### CAL_BARO0_ID (`INT32`) {#CAL_BARO0_ID} +### RM_MISS_SPD_GAIN (`FLOAT`) {#RM_MISS_SPD_GAIN} -Barometer 0 calibration device ID. +Tuning parameter for the speed reduction during waypoint transition. -Device ID of the barometer this calibration applies to. +The waypoint transition speed is calculated as: Transition_speed = Maximum_speed _ (1 - normalized_transition_angle _ RM_MISS_VEL_GAIN) The normalized transition angle is the angle between the line segment from prev-curr waypoint and curr-next waypoint interpolated from [0, 180] -> [0, 1]. Higher value -> More speed reduction during waypoint transitions. Set to -1 to disable any speed reduction during waypoint transition. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | -1 | 100 | 0.01 | -1 | -### CAL_BARO0_OFF (`FLOAT`) {#CAL_BARO0_OFF} +### RM_WHEEL_TRACK (`FLOAT`) {#RM_WHEEL_TRACK} -Barometer 0 offset. +Wheel track. + +Distance from the center of the right wheel to the center of the left wheel. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | 0 | 100 | 0.001 | 0 | m | -### CAL_BARO0_PRIO (`INT32`) {#CAL_BARO0_PRIO} +## Rover Position Control (Deprecated) -Barometer 0 priority. +### GND_L1_DAMPING (`FLOAT`) {#GND_L1_DAMPING} -**Values:** +L1 damping. -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +Damping factor for L1 control. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | 0.6 | 0.9 | 0.05 | 0.75 | -### CAL_BARO1_ID (`INT32`) {#CAL_BARO1_ID} +### GND_L1_DIST (`FLOAT`) {#GND_L1_DIST} -Barometer 1 calibration device ID. +L1 distance. -Device ID of the barometer this calibration applies to. +This is the distance at which the next waypoint is activated. This should be set to about 2-4x of GND_WHEEL_BASE and not smaller than one meter (due to GPS accuracy). | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 1.0 | 50.0 | 0.1 | 1.0 | m | -### CAL_BARO1_OFF (`FLOAT`) {#CAL_BARO1_OFF} +### GND_L1_PERIOD (`FLOAT`) {#GND_L1_PERIOD} -Barometer 1 offset. +L1 period. + +This is the L1 distance and defines the tracking point ahead of the rover it's following. Use values around 2-5m for a 0.3m wheel base. Tuning instructions: Shorten slowly during tuning until response is sharp without oscillation. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_BARO1_PRIO (`INT32`) {#CAL_BARO1_PRIO} - -Barometer 1 priority. +|   | 0.5 | 50.0 | 0.5 | 5.0 | m | -**Values:** +### GND_MAN_Y_MAX (`FLOAT`) {#GND_MAN_Y_MAX} -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +Max manual yaw rate. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | 0.0 | 400 | | 150.0 | deg/s | -### CAL_BARO2_ID (`INT32`) {#CAL_BARO2_ID} +### GND_MAX_ANG (`FLOAT`) {#GND_MAX_ANG} -Barometer 2 calibration device ID. +Maximum turn angle for Ackerman steering. -Device ID of the barometer this calibration applies to. +At a control output of 0, the steering wheels are at 0 radians. At a control output of 1, the steering wheels are at GND_MAX_ANG radians. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0.0 | 3.14159 | 0.01 | 0.7854 | rad | -### CAL_BARO2_OFF (`FLOAT`) {#CAL_BARO2_OFF} +### GND_SPEED_D (`FLOAT`) {#GND_SPEED_D} -Barometer 2 offset. +Speed proportional gain. + +This is the derivative gain for the speed closed loop controller | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_BARO2_PRIO (`INT32`) {#CAL_BARO2_PRIO} +|   | 0.00 | 50.0 | 0.005 | 0.001 | %m/s | -Barometer 2 priority. +### GND_SPEED_I (`FLOAT`) {#GND_SPEED_I} -**Values:** +Speed Integral gain. -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +This is the integral gain for the speed closed loop controller | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | 0.00 | 50.0 | 0.005 | 3.0 | %m/s | -### CAL_BARO3_ID (`INT32`) {#CAL_BARO3_ID} +### GND_SPEED_IMAX (`FLOAT`) {#GND_SPEED_IMAX} -Barometer 3 calibration device ID. +Speed integral maximum value. -Device ID of the barometer this calibration applies to. +This is the maxim value the integral can reach to prevent wind-up. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0.005 | 50.0 | 0.005 | 1.0 | %m/s | -### CAL_BARO3_OFF (`FLOAT`) {#CAL_BARO3_OFF} +### GND_SPEED_MAX (`FLOAT`) {#GND_SPEED_MAX} -Barometer 3 offset. +Maximum ground speed. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | 0.0 | 40 | 0.5 | 10.0 | m/s | -### CAL_BARO3_PRIO (`INT32`) {#CAL_BARO3_PRIO} - -Barometer 3 priority. +### GND_SPEED_P (`FLOAT`) {#GND_SPEED_P} -**Values:** +Speed proportional gain. -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +This is the proportional gain for the speed closed loop controller | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | 0.005 | 50.0 | 0.005 | 2.0 | %m/s | -### CAL_GYRO0_ID (`INT32`) {#CAL_GYRO0_ID} +### GND_SPEED_THR_SC (`FLOAT`) {#GND_SPEED_THR_SC} -Gyroscope 0 calibration device ID. +Speed to throttle scaler. -Device ID of the gyroscope this calibration applies to. +This is a gain to map the speed control output to the throttle linearly. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0.005 | 50.0 | 0.005 | 1.0 | %m/s | -### CAL_GYRO0_PRIO (`INT32`) {#CAL_GYRO0_PRIO} - -Gyroscope 0 priority. - -**Values:** +### GND_SPEED_TRIM (`FLOAT`) {#GND_SPEED_TRIM} -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +Trim ground speed. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | 0.0 | 40 | 0.5 | 3.0 | m/s | -### CAL_GYRO0_ROT (`INT32`) {#CAL_GYRO0_ROT} +### GND_SP_CTRL_MODE (`INT32`) {#GND_SP_CTRL_MODE} -Gyroscope 0 rotation relative to airframe. +Control mode for speed. -An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. +This allows the user to choose between closed loop gps speed or open loop cruise throttle speed **Values:** -- `-1`: Internal -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° -- `8`: Roll 180° -- `9`: Roll 180°, Yaw 45° -- `10`: Roll 180°, Yaw 90° -- `11`: Roll 180°, Yaw 135° -- `12`: Pitch 180° -- `13`: Roll 180°, Yaw 225° -- `14`: Roll 180°, Yaw 270° -- `15`: Roll 180°, Yaw 315° -- `16`: Roll 90° -- `17`: Roll 90°, Yaw 45° -- `18`: Roll 90°, Yaw 90° -- `19`: Roll 90°, Yaw 135° -- `20`: Roll 270° -- `21`: Roll 270°, Yaw 45° -- `22`: Roll 270°, Yaw 90° -- `23`: Roll 270°, Yaw 135° -- `24`: Pitch 90° -- `25`: Pitch 270° -- `26`: Pitch 180°, Yaw 90° -- `27`: Pitch 180°, Yaw 270° -- `28`: Roll 90°, Pitch 90° -- `29`: Roll 180°, Pitch 90° -- `30`: Roll 270°, Pitch 90° -- `31`: Roll 90°, Pitch 180° -- `32`: Roll 270°, Pitch 180° -- `33`: Roll 90°, Pitch 270° -- `34`: Roll 180°, Pitch 270° -- `35`: Roll 270°, Pitch 270° -- `36`: Roll 90°, Pitch 180°, Yaw 90° -- `37`: Roll 90°, Yaw 270° -- `38`: Roll 90°, Pitch 68°, Yaw 293° -- `39`: Pitch 315° -- `40`: Roll 90°, Pitch 315° +- `0`: open loop control +- `1`: close the loop with gps speed | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 40 | | -1 | - -### CAL_GYRO0_XOFF (`FLOAT`) {#CAL_GYRO0_XOFF} +|   | 0 | 1 | | 1 | -Gyroscope 0 X-axis offset. +### GND_THR_CRUISE (`FLOAT`) {#GND_THR_CRUISE} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +Cruise throttle. -### CAL_GYRO0_YOFF (`FLOAT`) {#CAL_GYRO0_YOFF} +This is the throttle setting required to achieve the desired cruise speed. 10% is ok for a traxxas stampede vxl with ESC set to training mode -Gyroscope 0 Y-axis offset. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 1.0 | 0.01 | 0.1 | norm | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +### GND_THR_MAX (`FLOAT`) {#GND_THR_MAX} -### CAL_GYRO0_ZOFF (`FLOAT`) {#CAL_GYRO0_ZOFF} +Throttle limit max. -Gyroscope 0 Z-axis offset. +This is the maximum throttle % that can be used by the controller. For a Traxxas stampede vxl with the ESC set to training, 30 % is enough -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 1.0 | 0.01 | 0.3 | norm | -### CAL_GYRO1_ID (`INT32`) {#CAL_GYRO1_ID} +### GND_THR_MIN (`FLOAT`) {#GND_THR_MIN} -Gyroscope 1 calibration device ID. +Throttle limit min. -Device ID of the gyroscope this calibration applies to. +This is the minimum throttle % that can be used by the controller. Set to 0 for rover | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### CAL_GYRO1_PRIO (`INT32`) {#CAL_GYRO1_PRIO} +|   | 0.0 | 1.0 | 0.01 | 0.0 | norm | -Gyroscope 1 priority. +### GND_WHEEL_BASE (`FLOAT`) {#GND_WHEEL_BASE} -**Values:** +Distance from front axle to rear axle. -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +A value of 0.31 is typical for 1/10 RC cars. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | 0.0 | | 0.01 | 0.31 | m | -### CAL_GYRO1_ROT (`INT32`) {#CAL_GYRO1_ROT} +## Rover Rate Control -Gyroscope 1 rotation relative to airframe. +### RO_YAW_ACCEL_LIM (`FLOAT`) {#RO_YAW_ACCEL_LIM} -An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. +Yaw acceleration limit. -**Values:** +Used to cap how quickly the magnitude of yaw rate setpoints can increase. Set to -1 to disable. -- `-1`: Internal -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° -- `8`: Roll 180° -- `9`: Roll 180°, Yaw 45° -- `10`: Roll 180°, Yaw 90° -- `11`: Roll 180°, Yaw 135° -- `12`: Pitch 180° -- `13`: Roll 180°, Yaw 225° -- `14`: Roll 180°, Yaw 270° -- `15`: Roll 180°, Yaw 315° -- `16`: Roll 90° -- `17`: Roll 90°, Yaw 45° -- `18`: Roll 90°, Yaw 90° -- `19`: Roll 90°, Yaw 135° -- `20`: Roll 270° -- `21`: Roll 270°, Yaw 45° -- `22`: Roll 270°, Yaw 90° -- `23`: Roll 270°, Yaw 135° -- `24`: Pitch 90° -- `25`: Pitch 270° -- `26`: Pitch 180°, Yaw 90° -- `27`: Pitch 180°, Yaw 270° -- `28`: Roll 90°, Pitch 90° -- `29`: Roll 180°, Pitch 90° -- `30`: Roll 270°, Pitch 90° -- `31`: Roll 90°, Pitch 180° -- `32`: Roll 270°, Pitch 180° -- `33`: Roll 90°, Pitch 270° -- `34`: Roll 180°, Pitch 270° -- `35`: Roll 270°, Pitch 270° -- `36`: Roll 90°, Pitch 180°, Yaw 90° -- `37`: Roll 90°, Yaw 270° -- `38`: Roll 90°, Pitch 68°, Yaw 293° -- `39`: Pitch 315° -- `40`: Roll 90°, Pitch 315° +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------- | +|   | -1 | 10000 | 0.01 | -1. | deg/s^2 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 40 | | -1 | +### RO_YAW_DECEL_LIM (`FLOAT`) {#RO_YAW_DECEL_LIM} -### CAL_GYRO1_XOFF (`FLOAT`) {#CAL_GYRO1_XOFF} +Yaw deceleration limit. -Gyroscope 1 X-axis offset. +Used to cap how quickly the magnitude of yaw rate setpoints can decrease. Set to -1 to disable. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------- | +|   | -1 | 10000 | 0.01 | -1. | deg/s^2 | -### CAL_GYRO1_YOFF (`FLOAT`) {#CAL_GYRO1_YOFF} +### RO_YAW_RATE_I (`FLOAT`) {#RO_YAW_RATE_I} -Gyroscope 1 Y-axis offset. +Integral gain for closed loop yaw rate controller. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 100 | 0.01 | 0. | -### CAL_GYRO1_ZOFF (`FLOAT`) {#CAL_GYRO1_ZOFF} +### RO_YAW_RATE_LIM (`FLOAT`) {#RO_YAW_RATE_LIM} -Gyroscope 1 Z-axis offset. +Yaw rate limit. + +Used to cap yaw rate setpoints and map controller inputs to yaw rate setpoints in Acro, Stabilized and Position mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | - -### CAL_GYRO2_ID (`INT32`) {#CAL_GYRO2_ID} +|   | 0 | 10000 | 0.01 | 0. | deg/s | -Gyroscope 2 calibration device ID. +### RO_YAW_RATE_P (`FLOAT`) {#RO_YAW_RATE_P} -Device ID of the gyroscope this calibration applies to. +Proportional gain for closed loop yaw rate controller. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### CAL_GYRO2_PRIO (`INT32`) {#CAL_GYRO2_PRIO} - -Gyroscope 2 priority. - -**Values:** +|   | 0 | 100 | 0.01 | 0. | -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +### RO_YAW_RATE_TH (`FLOAT`) {#RO_YAW_RATE_TH} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +Yaw rate measurement threshold. -### CAL_GYRO2_ROT (`INT32`) {#CAL_GYRO2_ROT} +The minimum threshold for the yaw rate measurement not to be interpreted as zero. -Gyroscope 2 rotation relative to airframe. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | 0 | 100 | 0.01 | 3. | deg/s | -An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. +### RO_YAW_STICK_DZ (`FLOAT`) {#RO_YAW_STICK_DZ} -**Values:** +Yaw stick deadzone. -- `-1`: Internal -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° -- `8`: Roll 180° -- `9`: Roll 180°, Yaw 45° -- `10`: Roll 180°, Yaw 90° -- `11`: Roll 180°, Yaw 135° -- `12`: Pitch 180° -- `13`: Roll 180°, Yaw 225° -- `14`: Roll 180°, Yaw 270° -- `15`: Roll 180°, Yaw 315° -- `16`: Roll 90° -- `17`: Roll 90°, Yaw 45° -- `18`: Roll 90°, Yaw 90° -- `19`: Roll 90°, Yaw 135° -- `20`: Roll 270° -- `21`: Roll 270°, Yaw 45° -- `22`: Roll 270°, Yaw 90° -- `23`: Roll 270°, Yaw 135° -- `24`: Pitch 90° -- `25`: Pitch 270° -- `26`: Pitch 180°, Yaw 90° -- `27`: Pitch 180°, Yaw 270° -- `28`: Roll 90°, Pitch 90° -- `29`: Roll 180°, Pitch 90° -- `30`: Roll 270°, Pitch 90° -- `31`: Roll 90°, Pitch 180° -- `32`: Roll 270°, Pitch 180° -- `33`: Roll 90°, Pitch 270° -- `34`: Roll 180°, Pitch 270° -- `35`: Roll 270°, Pitch 270° -- `36`: Roll 90°, Pitch 180°, Yaw 90° -- `37`: Roll 90°, Yaw 270° -- `38`: Roll 90°, Pitch 68°, Yaw 293° -- `39`: Pitch 315° -- `40`: Roll 90°, Pitch 315° +Percentage of stick input range that will be interpreted as zero around the stick centered value. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 40 | | -1 | +|   | 0 | 1 | 0.01 | 0.1 | -### CAL_GYRO2_XOFF (`FLOAT`) {#CAL_GYRO2_XOFF} +## Rover Velocity Control -Gyroscope 2 X-axis offset. +### RO_ACCEL_LIM (`FLOAT`) {#RO_ACCEL_LIM} + +Acceleration limit. + +Set to -1 to disable. For mecanum rovers this limit is used for longitudinal and lateral acceleration. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +|   | -1 | 100 | 0.01 | -1. | m/s^2 | -### CAL_GYRO2_YOFF (`FLOAT`) {#CAL_GYRO2_YOFF} +### RO_DECEL_LIM (`FLOAT`) {#RO_DECEL_LIM} -Gyroscope 2 Y-axis offset. +Deceleration limit. + +Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral deceleration. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +|   | -1 | 100 | 0.01 | -1. | m/s^2 | -### CAL_GYRO2_ZOFF (`FLOAT`) {#CAL_GYRO2_ZOFF} +### RO_JERK_LIM (`FLOAT`) {#RO_JERK_LIM} -Gyroscope 2 Z-axis offset. +Jerk limit. + +Set to -1 to disable. Note that if it is disabled the rover will not slow down when approaching waypoints in auto modes. For mecanum rovers this limit is used for longitudinal and lateral jerk. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +|   | -1 | 100 | 0.01 | -1. | m/s^3 | -### CAL_GYRO3_ID (`INT32`) {#CAL_GYRO3_ID} +### RO_MAX_THR_SPEED (`FLOAT`) {#RO_MAX_THR_SPEED} -Gyroscope 3 calibration device ID. +Speed the rover drives at maximum throttle. -Device ID of the gyroscope this calibration applies to. +Used to linearly map speeds [m/s] to throttle values [-1. 1]. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0 | 100 | 0.01 | 0. | m/s | -### CAL_GYRO3_PRIO (`INT32`) {#CAL_GYRO3_PRIO} +### RO_SPEED_I (`FLOAT`) {#RO_SPEED_I} -Gyroscope 3 priority. +Integral gain for ground speed controller. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 100 | 0.001 | 0. | -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +### RO_SPEED_LIM (`FLOAT`) {#RO_SPEED_LIM} + +Speed limit. + +Used to cap speed setpoints and map controller inputs to speed setpoints in Position mode. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | -1 | 100 | 0.01 | -1. | m/s | -### CAL_GYRO3_ROT (`INT32`) {#CAL_GYRO3_ROT} +### RO_SPEED_P (`FLOAT`) {#RO_SPEED_P} -Gyroscope 3 rotation relative to airframe. +Proportional gain for ground speed controller. -An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 100 | 0.01 | 0. | -**Values:** +### RO_SPEED_TH (`FLOAT`) {#RO_SPEED_TH} -- `-1`: Internal -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° -- `8`: Roll 180° -- `9`: Roll 180°, Yaw 45° -- `10`: Roll 180°, Yaw 90° -- `11`: Roll 180°, Yaw 135° -- `12`: Pitch 180° -- `13`: Roll 180°, Yaw 225° -- `14`: Roll 180°, Yaw 270° -- `15`: Roll 180°, Yaw 315° -- `16`: Roll 90° -- `17`: Roll 90°, Yaw 45° -- `18`: Roll 90°, Yaw 90° -- `19`: Roll 90°, Yaw 135° -- `20`: Roll 270° -- `21`: Roll 270°, Yaw 45° -- `22`: Roll 270°, Yaw 90° -- `23`: Roll 270°, Yaw 135° -- `24`: Pitch 90° -- `25`: Pitch 270° -- `26`: Pitch 180°, Yaw 90° -- `27`: Pitch 180°, Yaw 270° -- `28`: Roll 90°, Pitch 90° -- `29`: Roll 180°, Pitch 90° -- `30`: Roll 270°, Pitch 90° -- `31`: Roll 90°, Pitch 180° -- `32`: Roll 270°, Pitch 180° -- `33`: Roll 90°, Pitch 270° -- `34`: Roll 180°, Pitch 270° -- `35`: Roll 270°, Pitch 270° -- `36`: Roll 90°, Pitch 180°, Yaw 90° -- `37`: Roll 90°, Yaw 270° -- `38`: Roll 90°, Pitch 68°, Yaw 293° -- `39`: Pitch 315° -- `40`: Roll 90°, Pitch 315° +Speed measurement threshold. + +Set to -1 to disable. The minimum threshold for the speed measurement not to be interpreted as zero. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 40 | | -1 | +|   | 0 | 100 | 0.01 | 0.1 | m/s | -### CAL_GYRO3_XOFF (`FLOAT`) {#CAL_GYRO3_XOFF} +## Runway Takeoff -Gyroscope 3 X-axis offset. +### RWTO_MAX_THR (`FLOAT`) {#RWTO_MAX_THR} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +Throttle during runway takeoff. -### CAL_GYRO3_YOFF (`FLOAT`) {#CAL_GYRO3_YOFF} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 1.0 | 0.01 | 1.0 | norm | -Gyroscope 3 Y-axis offset. +### RWTO_NUDGE (`INT32`) {#RWTO_NUDGE} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +Enable use of yaw stick for nudging the wheel during runway ground roll. + +This is useful when map, GNSS, or yaw errors on ground are misaligned with what the operator intends for takeoff course. Particularly useful for skinny runways or if the wheel servo is a bit off trim. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | -### CAL_GYRO3_ZOFF (`FLOAT`) {#CAL_GYRO3_ZOFF} +### RWTO_PSP (`FLOAT`) {#RWTO_PSP} -Gyroscope 3 Z-axis offset. +Pitch setpoint during taxi / before takeoff rotation airspeed is reached. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | rad/s | +A taildragger with steerable wheel might need to pitch up a little to keep its wheel on the ground before airspeed to takeoff is reached. -### CAL_MAG0_ID (`INT32`) {#CAL_MAG0_ID} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -10.0 | 20.0 | 0.5 | 0.0 | deg | -Magnetometer 0 calibration device ID. +### RWTO_RAMP_TIME (`FLOAT`) {#RWTO_RAMP_TIME} -Device ID of the magnetometer this calibration applies to. +Throttle ramp up time for runway takeoff. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 1.0 | 15.0 | 0.1 | 2.0 | s | -### CAL_MAG0_PITCH (`FLOAT`) {#CAL_MAG0_PITCH} +### RWTO_ROT_AIRSPD (`FLOAT`) {#RWTO_ROT_AIRSPD} -Magnetometer 0 Custom Euler Pitch Angle. +Takeoff rotation airspeed. -Setting this parameter changes CAL_MAG0_ROT to "Custom Euler Angle" +The calibrated airspeed threshold during the takeoff ground roll when the plane should start rotating (pitching up). Must be less than the takeoff airspeed, will otherwise be capped at the takeoff airpeed (see FW_TKO_AIRSPD). If set <= 0.0, defaults to 0.9 \* takeoff airspeed (see FW_TKO_AIRSPD) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG0_PRIO (`INT32`) {#CAL_MAG0_PRIO} +|   | -1.0 | | 0.1 | -1.0 | m/s | -Magnetometer 0 priority. +### RWTO_ROT_TIME (`FLOAT`) {#RWTO_ROT_TIME} -**Values:** +Takeoff rotation time. -- `-1`: Uninitialized -- `0`: Disabled -- `1`: Min -- `25`: Low -- `50`: Medium (Default) -- `75`: High -- `100`: Max +This is the time desired to linearly ramp in takeoff pitch constraints during the takeoff rotation | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +|   | 0.1 | | 0.1 | 1.0 | s | -### CAL_MAG0_ROLL (`FLOAT`) {#CAL_MAG0_ROLL} +### RWTO_TKOFF (`INT32`) {#RWTO_TKOFF} -Magnetometer 0 Custom Euler Roll Angle. +Runway takeoff with landing gear. -Setting this parameter changes CAL_MAG0_ROT to "Custom Euler Angle" +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | +## SD Logging -### CAL_MAG0_ROT (`INT32`) {#CAL_MAG0_ROT} +### SDLOG_ALGORITHM (`INT32`) {#SDLOG_ALGORITHM} -Magnetometer 0 rotation relative to airframe. +Logfile Encryption algorithm. -An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -Set to "Custom Euler Angle" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW. +Selects the algorithm used for logfile encryption **Values:** -- `-1`: Internal -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° -- `8`: Roll 180° -- `9`: Roll 180°, Yaw 45° -- `10`: Roll 180°, Yaw 90° -- `11`: Roll 180°, Yaw 135° -- `12`: Pitch 180° -- `13`: Roll 180°, Yaw 225° -- `14`: Roll 180°, Yaw 270° -- `15`: Roll 180°, Yaw 315° -- `16`: Roll 90° -- `17`: Roll 90°, Yaw 45° -- `18`: Roll 90°, Yaw 90° -- `19`: Roll 90°, Yaw 135° -- `20`: Roll 270° -- `21`: Roll 270°, Yaw 45° -- `22`: Roll 270°, Yaw 90° -- `23`: Roll 270°, Yaw 135° -- `24`: Pitch 90° -- `25`: Pitch 270° -- `26`: Pitch 180°, Yaw 90° -- `27`: Pitch 180°, Yaw 270° -- `28`: Roll 90°, Pitch 90° -- `29`: Roll 180°, Pitch 90° -- `30`: Roll 270°, Pitch 90° -- `31`: Roll 90°, Pitch 180° -- `32`: Roll 270°, Pitch 180° -- `33`: Roll 90°, Pitch 270° -- `34`: Roll 180°, Pitch 270° -- `35`: Roll 270°, Pitch 270° -- `36`: Roll 90°, Pitch 180°, Yaw 90° -- `37`: Roll 90°, Yaw 270° -- `38`: Roll 90°, Pitch 68°, Yaw 293° -- `39`: Pitch 315° -- `40`: Roll 90°, Pitch 315° -- `100`: Custom Euler Angle +- `0`: Disabled +- `2`: XChaCha20 | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | | -1 | - -### CAL_MAG0_XCOMP (`FLOAT`) {#CAL_MAG0_XCOMP} +|   | | | | 2 | -Magnetometer 0 X Axis throttle compensation. +### SDLOG_BOOT_BAT (`INT32`) {#SDLOG_BOOT_BAT} -Coefficient describing linear relationship between -X component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] +Battery-only Logging. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +When enabled, logging will not start from boot if battery power is not detected (e.g. powered via USB on a test bench). This prevents extraneous flight logs from being created during bench testing. Note that this only applies to log-from-boot modes. This has no effect on arm-based modes. -### CAL_MAG0_XODIAG (`FLOAT`) {#CAL_MAG0_XODIAG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | -Magnetometer 0 X-axis off diagonal scale factor. +### SDLOG_DIRS_MAX (`INT32`) {#SDLOG_DIRS_MAX} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +Maximum number of log directories to keep. -### CAL_MAG0_XOFF (`FLOAT`) {#CAL_MAG0_XOFF} +If there are more log directories than this value, the system will delete the oldest directories during startup. In addition, the system will delete old logs if there is not enough free space left. The minimum amount is 300 MB. If this is set to 0, old directories will only be removed if the free space falls below the minimum. Note: this does not apply to mission log files. -Magnetometer 0 X-axis offset. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +### SDLOG_EXCH_KEY (`INT32`) {#SDLOG_EXCH_KEY} -### CAL_MAG0_XSCALE (`FLOAT`) {#CAL_MAG0_XSCALE} +Logfile Encryption key exchange key. -Magnetometer 0 X-axis scaling factor. +If the logfile is encrypted using a symmetric key algorithm, the used encryption key is generated at logging start and stored on the sdcard RSA2048 encrypted using this key. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +|   | 0 | 255 | | 1 | -### CAL_MAG0_YAW (`FLOAT`) {#CAL_MAG0_YAW} +### SDLOG_KEY (`INT32`) {#SDLOG_KEY} -Magnetometer 0 Custom Euler Yaw Angle. +Logfile Encryption key index. -Setting this parameter changes CAL_MAG0_ROT to "Custom Euler Angle" +Selects the key in keystore, used for encrypting the log. When using a symmetric encryption algorithm, the key is generated at logging start and kept stored in this index. For symmetric algorithms, the key is volatile and valid only for the duration of logging. The key is stored in encrypted format on the sdcard alongside the logfile, using an RSA2048 key defined by the SDLOG_EXCHANGE_KEY | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | +|   | 0 | 255 | | 2 | -### CAL_MAG0_YCOMP (`FLOAT`) {#CAL_MAG0_YCOMP} +### SDLOG_MISSION (`INT32`) {#SDLOG_MISSION} -Magnetometer 0 Y Axis throttle compensation. +Mission Log. -Coefficient describing linear relationship between -Y component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] +If enabled, a small additional "mission" log file will be written to the SD card. The log contains just those messages that are useful for tasks like generating flight statistics and geotagging. The different modes can be used to further reduce the logged data (and thus the log file size). For example, choose geotagging mode to only log data required for geotagging. Note that the normal/full log is still created, and contains all the data in the mission log (and more). -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +**Values:** -### CAL_MAG0_YODIAG (`FLOAT`) {#CAL_MAG0_YODIAG} +- `0`: Disabled +- `1`: All mission messages +- `2`: Geotagging messages -Magnetometer 0 Y-axis off diagonal scale factor. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +### SDLOG_MODE (`INT32`) {#SDLOG_MODE} -### CAL_MAG0_YOFF (`FLOAT`) {#CAL_MAG0_YOFF} +Logging Mode. -Magnetometer 0 Y-axis offset. +Determines when to start and stop logging. By default, logging is started when arming the system, and stopped when disarming. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +**Values:** -### CAL_MAG0_YSCALE (`FLOAT`) {#CAL_MAG0_YSCALE} +- `-1`: disabled +- `0`: when armed until disarm (default) +- `1`: from boot until disarm +- `2`: from boot until shutdown +- `3`: while manual input AUX1 >30% +- `4`: from 1st armed until shutdown -Magnetometer 0 Y-axis scaling factor. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +### SDLOG_PROFILE (`INT32`) {#SDLOG_PROFILE} -### CAL_MAG0_ZCOMP (`FLOAT`) {#CAL_MAG0_ZCOMP} +Logging topic profile (integer bitmask). -Magnetometer 0 Z Axis throttle compensation. +This integer bitmask controls the set and rates of logged topics. The default allows for general log analysis while keeping the log file size reasonably small. Enabling multiple sets leads to higher bandwidth requirements and larger log files. Set bits true to enable: 0 : Default set (used for general log analysis) 1 : Full rate estimator (EKF2) replay topics 2 : Topics for thermal calibration (high rate raw IMU and Baro sensor data) 3 : Topics for system identification (high rate actuator control and IMU data) 4 : Full rates for analysis of fast maneuvers (RC, attitude, rates and actuators) 5 : Debugging topics (debug\_\*.msg topics, for custom code) 6 : Topics for sensor comparison (low rate raw IMU, Baro and magnetometer data) 7 : Topics for computer vision and collision prevention 8 : Raw FIFO high-rate IMU (Gyro) 9 : Raw FIFO high-rate IMU (Accel) 10: Logging of mavlink tunnel message (useful for payload communication debugging) -Coefficient describing linear relationship between -Z component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] +**Bitmask:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +- `0`: Default set (general log analysis) +- `1`: Estimator replay (EKF2) +- `2`: Thermal calibration +- `3`: System identification +- `4`: High rate +- `5`: Debug +- `6`: Sensor comparison +- `7`: Computer Vision and Avoidance +- `8`: Raw FIFO high-rate IMU (Gyro) +- `9`: Raw FIFO high-rate IMU (Accel) +- `10`: Mavlink tunnel message logging +- `11`: High rate sensors -### CAL_MAG0_ZODIAG (`FLOAT`) {#CAL_MAG0_ZODIAG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 4095 | | 1 | -Magnetometer 0 Z-axis off diagonal scale factor. +### SDLOG_UTC_OFFSET (`INT32`) {#SDLOG_UTC_OFFSET} + +UTC offset (unit: min). + +the difference in hours and minutes from Coordinated Universal Time (UTC) for a your place and date. for example, In case of South Korea(UTC+09:00), UTC offset is 540 min (9\*60) refer to https://en.wikipedia.org/wiki/List_of_UTC_time_offsets | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | -1000 | 1000 | | 0 | min | -### CAL_MAG0_ZOFF (`FLOAT`) {#CAL_MAG0_ZOFF} +### SDLOG_UUID (`INT32`) {#SDLOG_UUID} -Magnetometer 0 Z-axis offset. +Log UUID. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +If set to 1, add an ID to the log, which uniquely identifies the vehicle -### CAL_MAG0_ZSCALE (`FLOAT`) {#CAL_MAG0_ZSCALE} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | -Magnetometer 0 Z-axis scaling factor. +## SITL + +### SIM_BAT_DRAIN (`FLOAT`) {#SIM_BAT_DRAIN} + +Simulator Battery drain interval. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | +|   | 1 | 86400 | 1 | 60 | s | -### CAL_MAG1_ID (`INT32`) {#CAL_MAG1_ID} +### SIM_BAT_ENABLE (`INT32`) {#SIM_BAT_ENABLE} -Magnetometer 1 calibration device ID. +Simulator Battery enabled. -Device ID of the magnetometer this calibration applies to. +Enable or disable the internal battery simulation. This is useful when the battery is simulated externally and interfaced with PX4 through MAVLink for example. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | + +### SIM_BAT_MIN_PCT (`FLOAT`) {#SIM_BAT_MIN_PCT} + +Simulator Battery minimal percentage. + +Can be used to alter the battery level during SITL- or HITL-simulation on the fly. Particularly useful for testing different low-battery behaviour. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0 | 100 | 0.1 | 50.0 | % | -### CAL_MAG1_PITCH (`FLOAT`) {#CAL_MAG1_PITCH} +## Sensor Calibration -Magnetometer 1 Custom Euler Pitch Angle. +### CAL_ACC0_ID (`INT32`) {#CAL_ACC0_ID} -Setting this parameter changes CAL_MAG1_ROT to "Custom Euler Angle" +Accelerometer 0 calibration device ID. + +Device ID of the accelerometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | +|   | | | | 0 | -### CAL_MAG1_PRIO (`INT32`) {#CAL_MAG1_PRIO} +### CAL_ACC0_PRIO (`INT32`) {#CAL_ACC0_PRIO} -Magnetometer 1 priority. +Accelerometer 0 priority. **Values:** @@ -31617,22 +27927,11 @@ Magnetometer 1 priority. | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | -1 | -### CAL_MAG1_ROLL (`FLOAT`) {#CAL_MAG1_ROLL} - -Magnetometer 1 Custom Euler Roll Angle. - -Setting this parameter changes CAL_MAG1_ROT to "Custom Euler Angle" - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG1_ROT (`INT32`) {#CAL_MAG1_ROT} +### CAL_ACC0_ROT (`INT32`) {#CAL_ACC0_ROT} -Magnetometer 1 rotation relative to airframe. +Accelerometer 0 rotation relative to airframe. An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -Set to "Custom Euler Angle" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW. **Values:** @@ -31678,159 +27977,72 @@ Set to "Custom Euler Angle" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1 - `38`: Roll 90°, Pitch 68°, Yaw 293° - `39`: Pitch 315° - `40`: Roll 90°, Pitch 315° -- `100`: Custom Euler Angle - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | | -1 | - -### CAL_MAG1_XCOMP (`FLOAT`) {#CAL_MAG1_XCOMP} - -Magnetometer 1 X Axis throttle compensation. - -Coefficient describing linear relationship between -X component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG1_XODIAG (`FLOAT`) {#CAL_MAG1_XODIAG} - -Magnetometer 1 X-axis off diagonal scale factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | -1 | 40 | | -1 | -### CAL_MAG1_XOFF (`FLOAT`) {#CAL_MAG1_XOFF} +### CAL_ACC0_XOFF (`FLOAT`) {#CAL_ACC0_XOFF} -Magnetometer 1 X-axis offset. +Accelerometer 0 X-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG1_XSCALE (`FLOAT`) {#CAL_MAG1_XSCALE} +### CAL_ACC0_XSCALE (`FLOAT`) {#CAL_ACC0_XSCALE} -Magnetometer 1 X-axis scaling factor. +Accelerometer 0 X-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG1_YAW (`FLOAT`) {#CAL_MAG1_YAW} - -Magnetometer 1 Custom Euler Yaw Angle. - -Setting this parameter changes CAL_MAG1_ROT to "Custom Euler Angle" - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG1_YCOMP (`FLOAT`) {#CAL_MAG1_YCOMP} - -Magnetometer 1 Y Axis throttle compensation. - -Coefficient describing linear relationship between -Y component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG1_YODIAG (`FLOAT`) {#CAL_MAG1_YODIAG} - -Magnetometer 1 Y-axis off diagonal scale factor. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG1_YOFF (`FLOAT`) {#CAL_MAG1_YOFF} +### CAL_ACC0_YOFF (`FLOAT`) {#CAL_ACC0_YOFF} -Magnetometer 1 Y-axis offset. +Accelerometer 0 Y-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG1_YSCALE (`FLOAT`) {#CAL_MAG1_YSCALE} +### CAL_ACC0_YSCALE (`FLOAT`) {#CAL_ACC0_YSCALE} -Magnetometer 1 Y-axis scaling factor. +Accelerometer 0 Y-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG1_ZCOMP (`FLOAT`) {#CAL_MAG1_ZCOMP} - -Magnetometer 1 Z Axis throttle compensation. - -Coefficient describing linear relationship between -Z component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG1_ZODIAG (`FLOAT`) {#CAL_MAG1_ZODIAG} - -Magnetometer 1 Z-axis off diagonal scale factor. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG1_ZOFF (`FLOAT`) {#CAL_MAG1_ZOFF} +### CAL_ACC0_ZOFF (`FLOAT`) {#CAL_ACC0_ZOFF} -Magnetometer 1 Z-axis offset. +Accelerometer 0 Z-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG1_ZSCALE (`FLOAT`) {#CAL_MAG1_ZSCALE} +### CAL_ACC0_ZSCALE (`FLOAT`) {#CAL_ACC0_ZSCALE} -Magnetometer 1 Z-axis scaling factor. +Accelerometer 0 Z-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG2_ID (`INT32`) {#CAL_MAG2_ID} +### CAL_ACC1_ID (`INT32`) {#CAL_ACC1_ID} -Magnetometer 2 calibration device ID. +Accelerometer 1 calibration device ID. -Device ID of the magnetometer this calibration applies to. +Device ID of the accelerometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### CAL_MAG2_PITCH (`FLOAT`) {#CAL_MAG2_PITCH} - -Magnetometer 2 Custom Euler Pitch Angle. - -Setting this parameter changes CAL_MAG2_ROT to "Custom Euler Angle" - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG2_PRIO (`INT32`) {#CAL_MAG2_PRIO} +### CAL_ACC1_PRIO (`INT32`) {#CAL_ACC1_PRIO} -Magnetometer 2 priority. +Accelerometer 1 priority. **Values:** @@ -31846,22 +28058,11 @@ Magnetometer 2 priority. | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | -1 | -### CAL_MAG2_ROLL (`FLOAT`) {#CAL_MAG2_ROLL} - -Magnetometer 2 Custom Euler Roll Angle. - -Setting this parameter changes CAL_MAG2_ROT to "Custom Euler Angle" - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG2_ROT (`INT32`) {#CAL_MAG2_ROT} +### CAL_ACC1_ROT (`INT32`) {#CAL_ACC1_ROT} -Magnetometer 2 rotation relative to airframe. +Accelerometer 1 rotation relative to airframe. An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -Set to "Custom Euler Angle" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW. **Values:** @@ -31907,159 +28108,72 @@ Set to "Custom Euler Angle" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2 - `38`: Roll 90°, Pitch 68°, Yaw 293° - `39`: Pitch 315° - `40`: Roll 90°, Pitch 315° -- `100`: Custom Euler Angle - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | | -1 | - -### CAL_MAG2_XCOMP (`FLOAT`) {#CAL_MAG2_XCOMP} - -Magnetometer 2 X Axis throttle compensation. - -Coefficient describing linear relationship between -X component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG2_XODIAG (`FLOAT`) {#CAL_MAG2_XODIAG} - -Magnetometer 2 X-axis off diagonal scale factor. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG2_XOFF (`FLOAT`) {#CAL_MAG2_XOFF} - -Magnetometer 2 X-axis offset. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | - -### CAL_MAG2_XSCALE (`FLOAT`) {#CAL_MAG2_XSCALE} - -Magnetometer 2 X-axis scaling factor. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | - -### CAL_MAG2_YAW (`FLOAT`) {#CAL_MAG2_YAW} - -Magnetometer 2 Custom Euler Yaw Angle. - -Setting this parameter changes CAL_MAG2_ROT to "Custom Euler Angle" - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG2_YCOMP (`FLOAT`) {#CAL_MAG2_YCOMP} - -Magnetometer 2 Y Axis throttle compensation. - -Coefficient describing linear relationship between -Y component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG2_YODIAG (`FLOAT`) {#CAL_MAG2_YODIAG} - -Magnetometer 2 Y-axis off diagonal scale factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | -1 | 40 | | -1 | -### CAL_MAG2_YOFF (`FLOAT`) {#CAL_MAG2_YOFF} +### CAL_ACC1_XOFF (`FLOAT`) {#CAL_ACC1_XOFF} -Magnetometer 2 Y-axis offset. +Accelerometer 1 X-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG2_YSCALE (`FLOAT`) {#CAL_MAG2_YSCALE} +### CAL_ACC1_XSCALE (`FLOAT`) {#CAL_ACC1_XSCALE} -Magnetometer 2 Y-axis scaling factor. +Accelerometer 1 X-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG2_ZCOMP (`FLOAT`) {#CAL_MAG2_ZCOMP} - -Magnetometer 2 Z Axis throttle compensation. - -Coefficient describing linear relationship between -Z component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG2_ZODIAG (`FLOAT`) {#CAL_MAG2_ZODIAG} - -Magnetometer 2 Z-axis off diagonal scale factor. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | - -### CAL_MAG2_ZOFF (`FLOAT`) {#CAL_MAG2_ZOFF} +### CAL_ACC1_YOFF (`FLOAT`) {#CAL_ACC1_YOFF} -Magnetometer 2 Z-axis offset. +Accelerometer 1 Y-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG2_ZSCALE (`FLOAT`) {#CAL_MAG2_ZSCALE} +### CAL_ACC1_YSCALE (`FLOAT`) {#CAL_ACC1_YSCALE} -Magnetometer 2 Z-axis scaling factor. +Accelerometer 1 Y-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG3_ID (`INT32`) {#CAL_MAG3_ID} +### CAL_ACC1_ZOFF (`FLOAT`) {#CAL_ACC1_ZOFF} -Magnetometer 3 calibration device ID. +Accelerometer 1 Z-axis offset. -Device ID of the magnetometer this calibration applies to. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | m/s^2 | + +### CAL_ACC1_ZSCALE (`FLOAT`) {#CAL_ACC1_ZSCALE} + +Accelerometer 1 Z-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG3_PITCH (`FLOAT`) {#CAL_MAG3_PITCH} +### CAL_ACC2_ID (`INT32`) {#CAL_ACC2_ID} -Magnetometer 3 Custom Euler Pitch Angle. +Accelerometer 2 calibration device ID. -Setting this parameter changes CAL_MAG3_ROT to "Custom Euler Angle" +Device ID of the accelerometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | +|   | | | | 0 | -### CAL_MAG3_PRIO (`INT32`) {#CAL_MAG3_PRIO} +### CAL_ACC2_PRIO (`INT32`) {#CAL_ACC2_PRIO} -Magnetometer 3 priority. +Accelerometer 2 priority. **Values:** @@ -32075,22 +28189,11 @@ Magnetometer 3 priority. | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | -1 | -### CAL_MAG3_ROLL (`FLOAT`) {#CAL_MAG3_ROLL} - -Magnetometer 3 Custom Euler Roll Angle. - -Setting this parameter changes CAL_MAG3_ROT to "Custom Euler Angle" - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | - -### CAL_MAG3_ROT (`INT32`) {#CAL_MAG3_ROT} +### CAL_ACC2_ROT (`INT32`) {#CAL_ACC2_ROT} -Magnetometer 3 rotation relative to airframe. +Accelerometer 2 rotation relative to airframe. An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -Set to "Custom Euler Angle" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW. **Values:** @@ -32136,1301 +28239,1467 @@ Set to "Custom Euler Angle" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3 - `38`: Roll 90°, Pitch 68°, Yaw 293° - `39`: Pitch 315° - `40`: Roll 90°, Pitch 315° -- `100`: Custom Euler Angle | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 100 | | -1 | - -### CAL_MAG3_XCOMP (`FLOAT`) {#CAL_MAG3_XCOMP} +|   | -1 | 40 | | -1 | -Magnetometer 3 X Axis throttle compensation. +### CAL_ACC2_XOFF (`FLOAT`) {#CAL_ACC2_XOFF} -Coefficient describing linear relationship between -X component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] +Accelerometer 2 X-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG3_XODIAG (`FLOAT`) {#CAL_MAG3_XODIAG} +### CAL_ACC2_XSCALE (`FLOAT`) {#CAL_ACC2_XSCALE} -Magnetometer 3 X-axis off diagonal scale factor. +Accelerometer 2 X-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG3_XOFF (`FLOAT`) {#CAL_MAG3_XOFF} +### CAL_ACC2_YOFF (`FLOAT`) {#CAL_ACC2_YOFF} -Magnetometer 3 X-axis offset. +Accelerometer 2 Y-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG3_XSCALE (`FLOAT`) {#CAL_MAG3_XSCALE} +### CAL_ACC2_YSCALE (`FLOAT`) {#CAL_ACC2_YSCALE} -Magnetometer 3 X-axis scaling factor. +Accelerometer 2 Y-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG3_YAW (`FLOAT`) {#CAL_MAG3_YAW} +### CAL_ACC2_ZOFF (`FLOAT`) {#CAL_ACC2_ZOFF} -Magnetometer 3 Custom Euler Yaw Angle. +Accelerometer 2 Z-axis offset. -Setting this parameter changes CAL_MAG3_ROT to "Custom Euler Angle" +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | m/s^2 | + +### CAL_ACC2_ZSCALE (`FLOAT`) {#CAL_ACC2_ZSCALE} + +Accelerometer 2 Z-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -180 | 180 | | 0.0 | deg | +|   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG3_YCOMP (`FLOAT`) {#CAL_MAG3_YCOMP} +### CAL_ACC3_ID (`INT32`) {#CAL_ACC3_ID} -Magnetometer 3 Y Axis throttle compensation. +Accelerometer 3 calibration device ID. -Coefficient describing linear relationship between -Y component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] +Device ID of the accelerometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | | | | 0 | -### CAL_MAG3_YODIAG (`FLOAT`) {#CAL_MAG3_YODIAG} +### CAL_ACC3_PRIO (`INT32`) {#CAL_ACC3_PRIO} -Magnetometer 3 Y-axis off diagonal scale factor. +Accelerometer 3 priority. + +**Values:** + +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | | | | -1 | -### CAL_MAG3_YOFF (`FLOAT`) {#CAL_MAG3_YOFF} +### CAL_ACC3_ROT (`INT32`) {#CAL_ACC3_ROT} -Magnetometer 3 Y-axis offset. +Accelerometer 3 rotation relative to airframe. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -### CAL_MAG3_YSCALE (`FLOAT`) {#CAL_MAG3_YSCALE} +**Values:** -Magnetometer 3 Y-axis scaling factor. +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 3.0 | | 1.0 | - -### CAL_MAG3_ZCOMP (`FLOAT`) {#CAL_MAG3_ZCOMP} +|   | -1 | 40 | | -1 | -Magnetometer 3 Z Axis throttle compensation. +### CAL_ACC3_XOFF (`FLOAT`) {#CAL_ACC3_XOFF} -Coefficient describing linear relationship between -Z component of magnetometer in body frame axis -and either current or throttle depending on value of CAL_MAG_COMP_TYP. -Unit for throttle-based compensation is [G] and -for current-based compensation [G/kA] +Accelerometer 3 X-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG3_ZODIAG (`FLOAT`) {#CAL_MAG3_ZODIAG} +### CAL_ACC3_XSCALE (`FLOAT`) {#CAL_ACC3_XSCALE} -Magnetometer 3 Z-axis off diagonal scale factor. +Accelerometer 3 X-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +|   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG3_ZOFF (`FLOAT`) {#CAL_MAG3_ZOFF} +### CAL_ACC3_YOFF (`FLOAT`) {#CAL_ACC3_YOFF} -Magnetometer 3 Z-axis offset. +Accelerometer 3 Y-axis offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +|   | | | | 0.0 | m/s^2 | -### CAL_MAG3_ZSCALE (`FLOAT`) {#CAL_MAG3_ZSCALE} +### CAL_ACC3_YSCALE (`FLOAT`) {#CAL_ACC3_YSCALE} -Magnetometer 3 Z-axis scaling factor. +Accelerometer 3 Y-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0.1 | 3.0 | | 1.0 | -### CAL_MAG_COMP_TYP (`INT32`) {#CAL_MAG_COMP_TYP} +### CAL_ACC3_ZOFF (`FLOAT`) {#CAL_ACC3_ZOFF} -Type of magnetometer compensation. +Accelerometer 3 Z-axis offset. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | m/s^2 | -- `0`: Disabled -- `1`: Throttle-based compensation -- `2`: Current-based compensation (battery_status instance 0) -- `3`: Current-based compensation (battery_status instance 1) +### CAL_ACC3_ZSCALE (`FLOAT`) {#CAL_ACC3_ZSCALE} + +Accelerometer 3 Z-axis scaling factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +|   | 0.1 | 3.0 | | 1.0 | -### SENS_DPRES_ANSC (`FLOAT`) {#SENS_DPRES_ANSC} +### CAL_BARO0_ID (`INT32`) {#CAL_BARO0_ID} -Differential pressure sensor analog scaling. +Barometer 0 calibration device ID. -Pick the appropriate scaling from the datasheet. -this number defines the (linear) conversion from voltage -to Pascal (pa). For the MPXV7002DP this is 1000. -NOTE: If the sensor always registers zero, try switching -the static and dynamic tubes. +Device ID of the barometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### SENS_DPRES_OFF (`FLOAT`) {#SENS_DPRES_OFF} - -Differential pressure sensor offset. +### CAL_BARO0_OFF (`FLOAT`) {#CAL_BARO0_OFF} -The offset (zero-reading) in Pascal +Barometer 0 offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0.0 | -### SENS_DPRES_REV (`INT32`) {#SENS_DPRES_REV} - -Reverse differential pressure sensor readings. - -Reverse the raw measurements of all differential pressure sensors. -This can be enabled if the sensors have static and dynamic ports swapped. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | +### CAL_BARO0_PRIO (`INT32`) {#CAL_BARO0_PRIO} -### SENS_FLOW_MAXHGT (`FLOAT`) {#SENS_FLOW_MAXHGT} +Barometer 0 priority. -Maximum height above ground when reliant on optical flow. +**Values:** -This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. -The height setpoint will be limited to be no greater than this value when the navigation system -is completely reliant on optical flow data and the height above ground estimate is valid. -The sensor may be usable above this height, but accuracy will progressively degrade. +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1.0 | 100.0 | 0.1 | 100. | m | - -### SENS_FLOW_MAXR (`FLOAT`) {#SENS_FLOW_MAXR} - -Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor. - -Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and -control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground -is less than 50% of this value. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 1.0 | | | 8. | rad/s | +|   | | | | -1 | -### SENS_FLOW_MINHGT (`FLOAT`) {#SENS_FLOW_MINHGT} +### CAL_BARO1_ID (`INT32`) {#CAL_BARO1_ID} -Minimum height above ground when reliant on optical flow. +Barometer 1 calibration device ID. -This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. -The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. +Device ID of the barometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1.0 | 0.1 | 0.08 | m | - -## Sensors - -### ADC_ADS1115_EN (`INT32`) {#ADC_ADS1115_EN} - -Enable external ADS1115 ADC. - -If enabled, the internal ADC is not used. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - -### BAT1_C_MULT (`FLOAT`) {#BAT1_C_MULT} - -Capacity/current multiplier for high-current capable SMBUS battery. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1.0 | - -### BAT1_SMBUS_MODEL (`INT32`) {#BAT1_SMBUS_MODEL} - -Battery device model. - -**Values:** - -- `0`: AutoDetect -- `1`: BQ40Z50 based -- `2`: BQ40Z80 based - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 2 | | 0 | +|   | | | | 0 | -### BATMON_ADDR_DFLT (`INT32`) {#BATMON_ADDR_DFLT} +### CAL_BARO1_OFF (`FLOAT`) {#CAL_BARO1_OFF} -I2C address for BatMon battery 1. +Barometer 1 offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 11 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -### BATMON_DRIVER_EN (`INT32`) {#BATMON_DRIVER_EN} +### CAL_BARO1_PRIO (`INT32`) {#CAL_BARO1_PRIO} -Parameter to enable BatMon module. +Barometer 1 priority. **Values:** +- `-1`: Uninitialized - `0`: Disabled -- `1`: Start on default I2C addr(BATMON_ADDR_DFLT) -- `2`: Autodetect I2C address (TODO) - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 2 | | 0 | - -### CAL_AIR_CMODEL (`INT32`) {#CAL_AIR_CMODEL} +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max -Airspeed sensor compensation model for the SDP3x. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | -1 | -Model with Pitot -CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. -CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. -Model without Pitot (1.5 mm tubes) -CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. -CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. -Tube Pressure Drop -CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. -CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot. +### CAL_BARO2_ID (`INT32`) {#CAL_BARO2_ID} -**Values:** +Barometer 2 calibration device ID. -- `0`: Model with Pitot -- `1`: Model without Pitot (1.5 mm tubes) -- `2`: Tube Pressure Drop +Device ID of the barometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### CAL_AIR_TUBED_MM (`FLOAT`) {#CAL_AIR_TUBED_MM} +### CAL_BARO2_OFF (`FLOAT`) {#CAL_BARO2_OFF} -Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation. +Barometer 2 offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1.5 | 100 | | 1.5 | mm | - -### CAL_AIR_TUBELEN (`FLOAT`) {#CAL_AIR_TUBELEN} - -Airspeed sensor tube length. - -See the CAL_AIR_CMODEL explanation on how this parameter should be set. +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 2.00 | | 0.2 | m | +### CAL_BARO2_PRIO (`INT32`) {#CAL_BARO2_PRIO} -### CAL_MAG_SIDES (`INT32`) {#CAL_MAG_SIDES} +Barometer 2 priority. -For legacy QGC support only. +**Values:** -Use SENS_MAG_SIDES instead +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 63 | - -### ILABS_MODE (`INT32`) {#ILABS_MODE} - -InertialLabs INS sensor mode configuration. +|   | | | | -1 | -Configures whether the driver outputs only raw sensor output (the default), -or additionally supplies INS data such as position and velocity estimates. +### CAL_BARO3_ID (`INT32`) {#CAL_BARO3_ID} -**Values:** +Barometer 3 calibration device ID. -- `0`: Sensors Only (default) -- `1`: INS +Device ID of the barometer this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 0 | -### IMU_ACCEL_CUTOFF (`FLOAT`) {#IMU_ACCEL_CUTOFF} - -Low pass filter cutoff frequency for accel. - -The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. -This only affects the signal sent to the controllers, not the estimators. 0 disables the filter. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | | 30.0 | Hz | - -### IMU_DGYRO_CUTOFF (`FLOAT`) {#IMU_DGYRO_CUTOFF} - -Cutoff frequency for angular acceleration (D-Term filter). - -The cutoff frequency for the 2nd order butterworth filter used on -the time derivative of the measured angular velocity, also known as -the D-term filter in the rate controller. The D-term uses the derivative of -the rate and thus is the most susceptible to noise. Therefore, using -a D-term filter allows to increase IMU_GYRO_CUTOFF, which -leads to reduced control latency and permits to increase the P gains. -A value of 0 disables the filter. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | 0.1 | 20.0 | Hz | - -### IMU_GYRO_CAL_EN (`INT32`) {#IMU_GYRO_CAL_EN} - -IMU gyro auto calibration enable. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | - -### IMU_GYRO_CUTOFF (`FLOAT`) {#IMU_GYRO_CUTOFF} - -Low pass filter cutoff frequency for gyro. - -The cutoff frequency for the 2nd order butterworth filter on the primary gyro. -This only affects the angular velocity sent to the controllers, not the estimators. -It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. -A value of 0 disables the filter. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | 0.1 | 40.0 | Hz | - -### IMU_GYRO_DNF_BW (`FLOAT`) {#IMU_GYRO_DNF_BW} - -IMU gyro ESC notch filter bandwidth. +### CAL_BARO3_OFF (`FLOAT`) {#CAL_BARO3_OFF} -Bandwidth per notch filter when using dynamic notch filtering with ESC RPM. +Barometer 3 offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 5 | 30 | 0.1 | 15. | Hz | - -### IMU_GYRO_DNF_EN (`INT32`) {#IMU_GYRO_DNF_EN} +|   | | | | 0.0 | -IMU gyro dynamic notch filtering. +### CAL_BARO3_PRIO (`INT32`) {#CAL_BARO3_PRIO} -Enable bank of dynamically updating notch filters. -Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN). +Barometer 3 priority. -**Bitmask:** +**Values:** -- `0`: ESC RPM -- `1`: FFT +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 3 | | 0 | +|   | | | | -1 | -### IMU_GYRO_DNF_HMC (`INT32`) {#IMU_GYRO_DNF_HMC} +### CAL_GYRO0_ID (`INT32`) {#CAL_GYRO0_ID} -IMU gyro dynamic notch filter harmonics. +Gyroscope 0 calibration device ID. -ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering. +Device ID of the gyroscope this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 7 | | 3 | +|   | | | | 0 | -### IMU_GYRO_DNF_MIN (`FLOAT`) {#IMU_GYRO_DNF_MIN} +### CAL_GYRO0_PRIO (`INT32`) {#CAL_GYRO0_PRIO} -IMU gyro dynamic notch filter minimum frequency. +Gyroscope 0 priority. -Minimum notch filter frequency in Hz. +**Values:** + +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | 0.1 | 25. | Hz | - -### IMU_GYRO_FFT_EN (`INT32`) {#IMU_GYRO_FFT_EN} - -IMU gyro FFT enable. +|   | | | | -1 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +### CAL_GYRO0_ROT (`INT32`) {#CAL_GYRO0_ROT} -### IMU_GYRO_FFT_LEN (`INT32`) {#IMU_GYRO_FFT_LEN} +Gyroscope 0 rotation relative to airframe. -IMU gyro FFT length. +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. **Values:** -- `256`: 256 -- `512`: 512 -- `1024`: 1024 -- `4096`: 4096 - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 512 | Hz | - -### IMU_GYRO_FFT_MAX (`FLOAT`) {#IMU_GYRO_FFT_MAX} - -IMU gyro FFT maximum frequency. +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 1000 | | 150. | Hz | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 40 | | -1 | -### IMU_GYRO_FFT_MIN (`FLOAT`) {#IMU_GYRO_FFT_MIN} +### CAL_GYRO0_XOFF (`FLOAT`) {#CAL_GYRO0_XOFF} -IMU gyro FFT minimum frequency. +Gyroscope 0 X-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 1000 | | 30. | Hz | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -### IMU_GYRO_FFT_SNR (`FLOAT`) {#IMU_GYRO_FFT_SNR} +### CAL_GYRO0_YOFF (`FLOAT`) {#CAL_GYRO0_YOFF} -IMU gyro FFT SNR. +Gyroscope 0 Y-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 30 | | 10. | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -### IMU_GYRO_NF0_BW (`FLOAT`) {#IMU_GYRO_NF0_BW} +### CAL_GYRO0_ZOFF (`FLOAT`) {#CAL_GYRO0_ZOFF} -Notch filter bandwidth for gyro. +Gyroscope 0 Z-axis offset. -The frequency width of the stop band for the 2nd order notch filter on the primary gyro. -See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency. -Applies to both angular velocity and angular acceleration sent to the controllers. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 100 | 0.1 | 20.0 | Hz | +### CAL_GYRO1_ID (`INT32`) {#CAL_GYRO1_ID} -### IMU_GYRO_NF0_FRQ (`FLOAT`) {#IMU_GYRO_NF0_FRQ} +Gyroscope 1 calibration device ID. -Notch filter frequency for gyro. +Device ID of the gyroscope this calibration applies to. -The center frequency for the 2nd order notch filter on the primary gyro. -This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. -This only affects the signal sent to the controllers, not the estimators. -Applies to both angular velocity and angular acceleration sent to the controllers. -See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter. -A value of 0 disables the filter. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | 0.1 | 0.0 | Hz | +### CAL_GYRO1_PRIO (`INT32`) {#CAL_GYRO1_PRIO} -### IMU_GYRO_NF1_BW (`FLOAT`) {#IMU_GYRO_NF1_BW} +Gyroscope 1 priority. -Notch filter 1 bandwidth for gyro. +**Values:** -The frequency width of the stop band for the 2nd order notch filter on the primary gyro. -See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency. -Applies to both angular velocity and angular acceleration sent to the controllers. +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 100 | 0.1 | 20.0 | Hz | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | -1 | -### IMU_GYRO_NF1_FRQ (`FLOAT`) {#IMU_GYRO_NF1_FRQ} +### CAL_GYRO1_ROT (`INT32`) {#CAL_GYRO1_ROT} -Notch filter 2 frequency for gyro. +Gyroscope 1 rotation relative to airframe. -The center frequency for the 2nd order notch filter on the primary gyro. -This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. -This only affects the signal sent to the controllers, not the estimators. -Applies to both angular velocity and angular acceleration sent to the controllers. -See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter. -A value of 0 disables the filter. +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | 0.1 | 0.0 | Hz | +**Values:** -### IMU_GYRO_RATEMAX (`INT32`) {#IMU_GYRO_RATEMAX} +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° -Gyro control data maximum publication rate (inner loop rate). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 40 | | -1 | -The maximum rate the gyro control data (vehicle_angular_velocity) will be -allowed to publish at. This is the loop rate for the rate controller and outputs. -Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting. +### CAL_GYRO1_XOFF (`FLOAT`) {#CAL_GYRO1_XOFF} -**Values:** +Gyroscope 1 X-axis offset. -- `100`: 100 Hz -- `250`: 250 Hz -- `400`: 400 Hz -- `800`: 800 Hz -- `1000`: 1000 Hz -- `2000`: 2000 Hz +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 100 | 2000 | | 400 | Hz | +### CAL_GYRO1_YOFF (`FLOAT`) {#CAL_GYRO1_YOFF} -### IMU_INTEG_RATE (`INT32`) {#IMU_INTEG_RATE} +Gyroscope 1 Y-axis offset. -IMU integration rate. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -The rate at which raw IMU data is integrated to produce delta angles and delta velocities. -Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2). +### CAL_GYRO1_ZOFF (`FLOAT`) {#CAL_GYRO1_ZOFF} -**Values:** +Gyroscope 1 Z-axis offset. -- `100`: 100 Hz -- `200`: 200 Hz -- `250`: 250 Hz -- `400`: 400 Hz +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 100 | 1000 | | 200 | Hz | +### CAL_GYRO2_ID (`INT32`) {#CAL_GYRO2_ID} -### INA220_CONFIG (`INT32`) {#INA220_CONFIG} +Gyroscope 2 calibration device ID. -INA220 Power Monitor Config. +Device ID of the gyroscope this calibration applies to. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 65535 | 1 | 8607 | - -### INA220_CUR_BAT (`FLOAT`) {#INA220_CUR_BAT} +|   | | | | 0 | -INA220 Power Monitor Battery Max Current. +### CAL_GYRO2_PRIO (`INT32`) {#CAL_GYRO2_PRIO} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 500.0 | 0.1 | 164.0 | +Gyroscope 2 priority. -### INA220_CUR_REG (`FLOAT`) {#INA220_CUR_REG} +**Values:** -INA220 Power Monitor Regulator Max Current. +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.1 | 500.0 | 0.1 | 164.0 | +|   | | | | -1 | -### INA220_SHUNT_BAT (`FLOAT`) {#INA220_SHUNT_BAT} +### CAL_GYRO2_ROT (`INT32`) {#CAL_GYRO2_ROT} -INA220 Power Monitor Battery Shunt. +Gyroscope 2 rotation relative to airframe. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | ----------- | -------- | ---------- | ------- | ---- | -|   | 0.000000001 | 0.1 | .000000001 | 0.0005 | +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -### INA220_SHUNT_REG (`FLOAT`) {#INA220_SHUNT_REG} +**Values:** -INA220 Power Monitor Regulator Shunt. +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | ----------- | -------- | ---------- | ------- | ---- | -|   | 0.000000001 | 0.1 | .000000001 | 0.0005 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 40 | | -1 | -### INA226_CONFIG (`INT32`) {#INA226_CONFIG} +### CAL_GYRO2_XOFF (`FLOAT`) {#CAL_GYRO2_XOFF} -INA226 Power Monitor Config. +Gyroscope 2 X-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 65535 | 1 | 18139 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -### INA226_CURRENT (`FLOAT`) {#INA226_CURRENT} +### CAL_GYRO2_YOFF (`FLOAT`) {#CAL_GYRO2_YOFF} -INA226 Power Monitor Max Current. +Gyroscope 2 Y-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0.1 | 200.0 | 0.1 | 164.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -### INA226_SHUNT (`FLOAT`) {#INA226_SHUNT} +### CAL_GYRO2_ZOFF (`FLOAT`) {#CAL_GYRO2_ZOFF} -INA226 Power Monitor Shunt. +Gyroscope 2 Z-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | ----------- | -------- | ---------- | ------- | ---- | -| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -### INA228_CONFIG (`INT32`) {#INA228_CONFIG} +### CAL_GYRO3_ID (`INT32`) {#CAL_GYRO3_ID} -INA228 Power Monitor Config. +Gyroscope 3 calibration device ID. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 65535 | 1 | 63779 | +Device ID of the gyroscope this calibration applies to. -### INA228_CURRENT (`FLOAT`) {#INA228_CURRENT} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -INA228 Power Monitor Max Current. +### CAL_GYRO3_PRIO (`INT32`) {#CAL_GYRO3_PRIO} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0.1 | 327.68 | 0.1 | 327.68 | +Gyroscope 3 priority. -### INA228_SHUNT (`FLOAT`) {#INA228_SHUNT} +**Values:** -INA228 Power Monitor Shunt. +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | ----------- | -------- | ---------- | ------- | ---- | -| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | -1 | -### INA238_CURRENT (`FLOAT`) {#INA238_CURRENT} +### CAL_GYRO3_ROT (`INT32`) {#CAL_GYRO3_ROT} -INA238 Power Monitor Max Current. +Gyroscope 3 rotation relative to airframe. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0.1 | 327.68 | 0.1 | 327.68 | +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. -### INA238_SHUNT (`FLOAT`) {#INA238_SHUNT} +**Values:** -INA238 Power Monitor Shunt. +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | ----------- | -------- | ---------- | ------- | ---- | -| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 40 | | -1 | -### MS_ACCEL_RANGE (`INT32`) {#MS_ACCEL_RANGE} +### CAL_GYRO3_XOFF (`FLOAT`) {#CAL_GYRO3_XOFF} -MicroStrain accelerometer range. +Gyroscope 3 X-axis offset. --1 = Will not be configured, and will use the device default range. -Ranges vary by device and map to integer codes. Check the device's [User Manual](https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com) for supported ranges and set the corresponding integer. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | -1 | +### CAL_GYRO3_YOFF (`FLOAT`) {#CAL_GYRO3_YOFF} -### MS_ALIGNMENT (`INT32`) {#MS_ALIGNMENT} +Gyroscope 3 Y-axis offset. -MicroStrain heading alignment type. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -Select the source of heading alignment. +### CAL_GYRO3_ZOFF (`FLOAT`) {#CAL_GYRO3_ZOFF} -**Bitmask:** +Gyroscope 3 Z-axis offset. -- `0`: Dual-antenna GNSS -- `1`: GNSS kinematic (requires motion, e.g. a GNSS velocity) -- `2`: Magnetometer -- `3`: External Heading (first valid external heading will be used to initialize the filter) +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | rad/s | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 15 | | 2 | +### CAL_MAG0_ID (`INT32`) {#CAL_MAG0_ID} -### MS_BARO_RATE_HZ (`INT32`) {#MS_BARO_RATE_HZ} +Magnetometer 0 calibration device ID. -MicroStrain barometer data rate. +Device ID of the magnetometer this calibration applies to. -Barometer data rate (Hz). -Valid rates: 0 or any factor of 1000. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | | 50 | +### CAL_MAG0_PITCH (`FLOAT`) {#CAL_MAG0_PITCH} -### MS_EHEAD_YAW (`FLOAT`) {#MS_EHEAD_YAW} +Magnetometer 0 Custom Euler Pitch Angle. -MicroStrain External Heading Orientation (Yaw). +Setting this parameter changes CAL_MAG0_ROT to "Custom Euler Angle" -The orientation of the device (Radians) with respect to the vehicle frame around the z axis. -Requires MS_EXT_HEAD_EN to be enabled to be used. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +### CAL_MAG0_PRIO (`INT32`) {#CAL_MAG0_PRIO} -### MS_EMAG_PTCH (`FLOAT`) {#MS_EMAG_PTCH} +Magnetometer 0 priority. -MicroStrain External Magnetometer Orientation (Pitch). +**Values:** -The orientation of the device (Radians) with respect to the vehicle frame around the y axis. -Requires MS_EXT_MAG_EN to be enabled to be used. +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | -1 | -### MS_EMAG_ROLL (`FLOAT`) {#MS_EMAG_ROLL} +### CAL_MAG0_ROLL (`FLOAT`) {#CAL_MAG0_ROLL} -MicroStrain External Magnetometer Orientation (Roll). +Magnetometer 0 Custom Euler Roll Angle. -The orientation of the device (Radians) with respect to the vehicle frame around the x axis. -Requires MS_EXT_MAG_EN to be enabled to be used. +Setting this parameter changes CAL_MAG0_ROT to "Custom Euler Angle" -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -### MS_EMAG_UNCERT (`FLOAT`) {#MS_EMAG_UNCERT} +### CAL_MAG0_ROT (`INT32`) {#CAL_MAG0_ROT} -MicroStrain external magnetometer uncertainty. +Magnetometer 0 rotation relative to airframe. -The 1-sigma uncertainty (in Gauss) for all axes, which will remain constant across all aiding measurements. -Requires MS_EXT_MAG_EN to be enabled to be used. +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to "Custom Euler Angle" to define the rotation using CAL_MAG0_ROLL, CAL_MAG0_PITCH and CAL_MAG0_YAW. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.1 | +**Values:** -### MS_EMAG_YAW (`FLOAT`) {#MS_EMAG_YAW} +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° +- `100`: Custom Euler Angle -MicroStrain External Magnetometer Orientation (Yaw). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 100 | | -1 | -The orientation of the device (Radians) with respect to the vehicle frame around the z axis. -Requires MS_EXT_MAG_EN to be enabled to be used. +### CAL_MAG0_XCOMP (`FLOAT`) {#CAL_MAG0_XCOMP} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Magnetometer 0 X Axis throttle compensation. -### MS_EXT_HEAD_EN (`INT32`) {#MS_EXT_HEAD_EN} +Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -Enable MicroStrain external heading aiding. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -Toggles external heading as an aiding measurement. -If enabled, the filter will be configured to accept external heading as an aiding meaurement. +### CAL_MAG0_XODIAG (`FLOAT`) {#CAL_MAG0_XODIAG} -**Values:** +Magnetometer 0 X-axis off diagonal scale factor. -- `0`: Disabled -- `1`: Enabled +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +### CAL_MAG0_XOFF (`FLOAT`) {#CAL_MAG0_XOFF} -### MS_EXT_MAG_EN (`INT32`) {#MS_EXT_MAG_EN} +Magnetometer 0 X-axis offset. -Enable MicroStrain external magnetometer aiding. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -Toggles external magnetometer aiding in the device filter. +### CAL_MAG0_XSCALE (`FLOAT`) {#CAL_MAG0_XSCALE} -**Values:** +Magnetometer 0 X-axis scaling factor. -- `0`: Disabled -- `1`: Enabled +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +### CAL_MAG0_YAW (`FLOAT`) {#CAL_MAG0_YAW} -### MS_FILT_RATE_HZ (`INT32`) {#MS_FILT_RATE_HZ} +Magnetometer 0 Custom Euler Yaw Angle. -MicroStrain EKF data rate. +Setting this parameter changes CAL_MAG0_ROT to "Custom Euler Angle" -The rate at which the INS data is published (Hz). -Valid rates: 0 or any factor of 1000. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | | 250 | +### CAL_MAG0_YCOMP (`FLOAT`) {#CAL_MAG0_YCOMP} -### MS_GNSS_AID_SRC (`INT32`) {#MS_GNSS_AID_SRC} +Magnetometer 0 Y Axis throttle compensation. -MicroStrain GNSS aiding source control. +Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -Select the source of gnss aiding (GNSS/INS). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -**Values:** +### CAL_MAG0_YODIAG (`FLOAT`) {#CAL_MAG0_YODIAG} -- `1`: All internal receivers -- `2`: External GNSS messages -- `3`: GNSS receiver 1 only -- `4`: GNSS receiver 2 only +Magnetometer 0 Y-axis off diagonal scale factor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -### MS_GNSS_OFF1_X (`FLOAT`) {#MS_GNSS_OFF1_X} +### CAL_MAG0_YOFF (`FLOAT`) {#CAL_MAG0_YOFF} -MicroStrain GNSS lever arm offset 1 (X). +Magnetometer 0 Y-axis offset. -Lever arm offset (m) in the X direction for the external GNSS receiver. -In the case of a dual antenna setup, this is antenna 1. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +### CAL_MAG0_YSCALE (`FLOAT`) {#CAL_MAG0_YSCALE} -### MS_GNSS_OFF1_Y (`FLOAT`) {#MS_GNSS_OFF1_Y} +Magnetometer 0 Y-axis scaling factor. -MicroStrain GNSS lever arm offset 1 (Y). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -Lever arm offset (m) in the Y direction for the external GNSS receiver. -In the case of a dual antenna setup, this is antenna 1. +### CAL_MAG0_ZCOMP (`FLOAT`) {#CAL_MAG0_ZCOMP} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Magnetometer 0 Z Axis throttle compensation. -### MS_GNSS_OFF1_Z (`FLOAT`) {#MS_GNSS_OFF1_Z} +Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -MicroStrain GNSS lever arm offset 1 (Z). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -Lever arm offset (m) in the Z direction for the external GNSS receiver. -In the case of a dual antenna setup, this is antenna 1. +### CAL_MAG0_ZODIAG (`FLOAT`) {#CAL_MAG0_ZODIAG} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Magnetometer 0 Z-axis off diagonal scale factor. -### MS_GNSS_OFF2_X (`FLOAT`) {#MS_GNSS_OFF2_X} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -MicroStrain GNSS lever arm offset 2 (X). +### CAL_MAG0_ZOFF (`FLOAT`) {#CAL_MAG0_ZOFF} -Lever arm offset (m) in the X direction for antenna 2 -This will only be used if the device supports a dual antenna setup. +Magnetometer 0 Z-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -### MS_GNSS_OFF2_Y (`FLOAT`) {#MS_GNSS_OFF2_Y} +### CAL_MAG0_ZSCALE (`FLOAT`) {#CAL_MAG0_ZSCALE} -MicroStrain GNSS lever arm offset 2 (Y). +Magnetometer 0 Z-axis scaling factor. -Lever arm offset (m) in the Y direction for antenna 2. -This will only be used if the device supports a dual antenna setup. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +### CAL_MAG1_ID (`INT32`) {#CAL_MAG1_ID} -### MS_GNSS_OFF2_Z (`FLOAT`) {#MS_GNSS_OFF2_Z} +Magnetometer 1 calibration device ID. -MicroStrain GNSS lever arm offset 2 (Z). +Device ID of the magnetometer this calibration applies to. -Lever arm offset (m) in the X direction for antenna 2. -This will only be used if the device supports a dual antenna setup. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +### CAL_MAG1_PITCH (`FLOAT`) {#CAL_MAG1_PITCH} -### MS_GNSS_RATE_HZ (`INT32`) {#MS_GNSS_RATE_HZ} +Magnetometer 1 Custom Euler Pitch Angle. -MicroStrain GNSS data rate. +Setting this parameter changes CAL_MAG1_ROT to "Custom Euler Angle" -GNSS receiver 1 and 2 data rate (Hz). -Valid rates: 0, 1 or 5. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 5 | | 5 | +### CAL_MAG1_PRIO (`INT32`) {#CAL_MAG1_PRIO} -### MS_GYRO_RANGE (`INT32`) {#MS_GYRO_RANGE} +Magnetometer 1 priority. -MicroStrain gyroscope range. +**Values:** --1 = Will not be configured, and will use the device default range. -Ranges vary by device and map to integer codes. Check the device's [User Manual](https://www.hbkworld.com/en/products/transducers/inertial-sensors#!ref_microstrain.com) for supported ranges and set the corresponding integer. +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | -1 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | -1 | -### MS_IMU_RATE_HZ (`INT32`) {#MS_IMU_RATE_HZ} +### CAL_MAG1_ROLL (`FLOAT`) {#CAL_MAG1_ROLL} -MicroStrain IMU data rate. +Magnetometer 1 Custom Euler Roll Angle. -Accelerometer and Gyroscope data rate (Hz). -Valid rates: 0 or any factor of 1000. +Setting this parameter changes CAL_MAG1_ROT to "Custom Euler Angle" -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | | 500 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -### MS_INT_HEAD_EN (`INT32`) {#MS_INT_HEAD_EN} +### CAL_MAG1_ROT (`INT32`) {#CAL_MAG1_ROT} -Enable MicroStrain internal heading aiding. +Magnetometer 1 rotation relative to airframe. -Toggles internal heading as an aiding measurement. -If dual antennas are supported (CV7-GNSS/INS). The filter will be configured to use dual antenna heading as an aiding measurement. +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to "Custom Euler Angle" to define the rotation using CAL_MAG1_ROLL, CAL_MAG1_PITCH and CAL_MAG1_YAW. **Values:** -- `0`: Disabled -- `1`: Enabled +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° +- `100`: Custom Euler Angle -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 100 | | -1 | -### MS_INT_MAG_EN (`INT32`) {#MS_INT_MAG_EN} +### CAL_MAG1_XCOMP (`FLOAT`) {#CAL_MAG1_XCOMP} -Enable MicroStrain internal magnetometer. +Magnetometer 1 X Axis throttle compensation. -Toggles internal magnetometer aiding in the device filter. +Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -- `0`: Disabled -- `1`: Enabled +### CAL_MAG1_XODIAG (`FLOAT`) {#CAL_MAG1_XODIAG} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +Magnetometer 1 X-axis off diagonal scale factor. -### MS_MAG_RATE_HZ (`INT32`) {#MS_MAG_RATE_HZ} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -MicroStrain magnetometer data rate. +### CAL_MAG1_XOFF (`FLOAT`) {#CAL_MAG1_XOFF} -Magnetometer data rate (Hz). -Valid rates: 0 or any factor of 1000. +Magnetometer 1 X-axis offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1000 | | 50 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -### MS_MODE (`INT32`) {#MS_MODE} +### CAL_MAG1_XSCALE (`FLOAT`) {#CAL_MAG1_XSCALE} -MicroStrain device mode. +Magnetometer 1 X-axis scaling factor. -Sensor mode publishes raw IMU data to be used by EKF2. INS data from the device is published to the external INS topics. -INS mode publishes the INS data to the vehicle topics to be used for navigation. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -**Values:** +### CAL_MAG1_YAW (`FLOAT`) {#CAL_MAG1_YAW} -- `0`: Sensor Mode -- `1`: INS Mode +Magnetometer 1 Custom Euler Yaw Angle. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +Setting this parameter changes CAL_MAG1_ROT to "Custom Euler Angle" -### MS_OFLW_OFF_X (`FLOAT`) {#MS_OFLW_OFF_X} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -MicroStrain optical flow offset (X). +### CAL_MAG1_YCOMP (`FLOAT`) {#CAL_MAG1_YCOMP} -Offset (m) in the X direction if an Optical Flow sensor is connected. -Requires MS_OPT_FLOW_EN to be enabled to be used. +Magnetometer 1 Y Axis throttle compensation. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -### MS_OFLW_OFF_Y (`FLOAT`) {#MS_OFLW_OFF_Y} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -MicroStrain optical flow offset (Y). +### CAL_MAG1_YODIAG (`FLOAT`) {#CAL_MAG1_YODIAG} -Offset (m) in the Y direction if an Optical Flow sensor is connected. -Requires MS_OPT_FLOW_EN to be enabled to be used. +Magnetometer 1 Y-axis off diagonal scale factor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -### MS_OFLW_OFF_Z (`FLOAT`) {#MS_OFLW_OFF_Z} +### CAL_MAG1_YOFF (`FLOAT`) {#CAL_MAG1_YOFF} -MicroStrain optical flow offset (Z). +Magnetometer 1 Y-axis offset. -Offset (m) in the Z direction if an Optical Flow sensor is connected. -Requires MS_OPT_FLOW_EN to be enabled to be used. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +### CAL_MAG1_YSCALE (`FLOAT`) {#CAL_MAG1_YSCALE} -### MS_OFLW_UNCERT (`FLOAT`) {#MS_OFLW_UNCERT} +Magnetometer 1 Y-axis scaling factor. -MicroStrain optical flow uncertainty. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -The 1-sigma uncertainty (in m/s) for the X and Y axes, which will remain constant across all aiding measurements. -The Z axis is not used for aiding. -Requires MS_OPT_FLOW_EN to be enabled to be used. +### CAL_MAG1_ZCOMP (`FLOAT`) {#CAL_MAG1_ZCOMP} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.1 | +Magnetometer 1 Z Axis throttle compensation. -### MS_OPT_FLOW_EN (`INT32`) {#MS_OPT_FLOW_EN} +Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -Enable MicroStrain optical flow aiding. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -Toggles body frame velocity as an aiding measurement. -The driver uses the body frame velocity from the optical flow sensor as the aiding measurements. +### CAL_MAG1_ZODIAG (`FLOAT`) {#CAL_MAG1_ZODIAG} -**Values:** +Magnetometer 1 Z-axis off diagonal scale factor. -- `0`: Disabled -- `1`: Enabled +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +### CAL_MAG1_ZOFF (`FLOAT`) {#CAL_MAG1_ZOFF} -### MS_SENSOR_PTCH (`FLOAT`) {#MS_SENSOR_PTCH} +Magnetometer 1 Z-axis offset. -MicroStrain Sensor to Vehicle Transform (Pitch). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -The orientation of the device (Radians) with respect to the vehicle frame around the y axis. -Requires MS_SVT_EN to be enabled to be used. +### CAL_MAG1_ZSCALE (`FLOAT`) {#CAL_MAG1_ZSCALE} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Magnetometer 1 Z-axis scaling factor. -### MS_SENSOR_ROLL (`FLOAT`) {#MS_SENSOR_ROLL} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -MicroStrain Sensor to vehicle transform (Roll). +### CAL_MAG2_ID (`INT32`) {#CAL_MAG2_ID} -The orientation of the device (Radians) with respect to the vehicle frame around the x axis. -Requires MS_SVT_EN to be enabled to be used. +Magnetometer 2 calibration device ID. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Device ID of the magnetometer this calibration applies to. -### MS_SENSOR_YAW (`FLOAT`) {#MS_SENSOR_YAW} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -MicroStrain Sensor to Vehicle Transform (Yaw). +### CAL_MAG2_PITCH (`FLOAT`) {#CAL_MAG2_PITCH} -The orientation of the device (Radians) with respect to the vehicle frame around the z axis. -Requires MS_SVT_EN to be enabled to be used. +Magnetometer 2 Custom Euler Pitch Angle. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0.0 | +Setting this parameter changes CAL_MAG2_ROT to "Custom Euler Angle" -### MS_SVT_EN (`INT32`) {#MS_SVT_EN} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -Enables Microstrain sensor to vehicle transform. +### CAL_MAG2_PRIO (`INT32`) {#CAL_MAG2_PRIO} -If the sensor has a different orientation with respect to the vehicle. This will enable a transform to correct itself. -The transform is described by MS_SENSOR_ROLL, MS_SENSOR_PITCH, MS_SENSOR_YAW. +Magnetometer 2 priority. **Values:** +- `-1`: Uninitialized - `0`: Disabled -- `1`: Enabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | -1 | -### PCF8583_MAGNET (`INT32`) {#PCF8583_MAGNET} +### CAL_MAG2_ROLL (`FLOAT`) {#CAL_MAG2_ROLL} -PCF8583 rotorfreq (i2c) pulse count. +Magnetometer 2 Custom Euler Roll Angle. -Nmumber of signals per rotation of actuator +Setting this parameter changes CAL_MAG2_ROT to "Custom Euler Angle" -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | | | 2 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -### PCF8583_POOL (`INT32`) {#PCF8583_POOL} +### CAL_MAG2_ROT (`INT32`) {#CAL_MAG2_ROT} -PCF8583 rotorfreq (i2c) pool interval. +Magnetometer 2 rotation relative to airframe. -Determines how often the sensor is read out. +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to "Custom Euler Angle" to define the rotation using CAL_MAG2_ROLL, CAL_MAG2_PITCH and CAL_MAG2_YAW. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1000000 | us | +**Values:** -### PCF8583_RESET (`INT32`) {#PCF8583_RESET} +- `-1`: Internal +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° +- `100`: Custom Euler Angle -PCF8583 rotorfreq (i2c) pulse reset value. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 100 | | -1 | + +### CAL_MAG2_XCOMP (`FLOAT`) {#CAL_MAG2_XCOMP} -Internal device counter is reset to 0 when overrun this value, -counter is able to store up to 6 digits -reset of counter takes some time - measurement with reset has worse accuracy. -0 means reset counter after every measurement. +Magnetometer 2 X Axis throttle compensation. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 500000 | +Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -### SBG_BAUDRATE (`INT32`) {#SBG_BAUDRATE} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -sbgECom driver baudrate. +### CAL_MAG2_XODIAG (`FLOAT`) {#CAL_MAG2_XODIAG} -Baudrate used by default for serial communication between PX4 -and SBG Systems INS through sbgECom driver. +Magnetometer 2 X-axis off diagonal scale factor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 9600 | 921600 | | 921600 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -### SBG_CONFIGURE_EN (`INT32`) {#SBG_CONFIGURE_EN} +### CAL_MAG2_XOFF (`FLOAT`) {#CAL_MAG2_XOFF} -sbgECom driver INS configuration enable. +Magnetometer 2 X-axis offset. -Enable SBG Systems INS configuration through sbgECom driver -on start. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | +### CAL_MAG2_XSCALE (`FLOAT`) {#CAL_MAG2_XSCALE} -### SBG_MODE (`INT32`) {#SBG_MODE} +Magnetometer 2 X-axis scaling factor. -sbgECom driver mode. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -Modes available for sbgECom driver. -In Sensors Only mode, use external IMU and magnetometer. -In GNSS mode, use external GNSS in addition to sensors only mode. -In INS mode, use external Kalman Filter in addition to GNSS mode. -In INS mode, requires EKF2_EN 0. Keeping both enabled -can lead to an unexpected behavior and vehicle instability. +### CAL_MAG2_YAW (`FLOAT`) {#CAL_MAG2_YAW} -**Values:** +Magnetometer 2 Custom Euler Yaw Angle. -- `0`: Sensors Only -- `1`: GNSS -- `2`: INS (default) +Setting this parameter changes CAL_MAG2_ROT to "Custom Euler Angle" | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 2 | +|   | -180 | 180 | | 0.0 | deg | -### SENS_AFBR_HYSTER (`INT32`) {#SENS_AFBR_HYSTER} +### CAL_MAG2_YCOMP (`FLOAT`) {#CAL_MAG2_YCOMP} -AFBR Rangefinder Short/Long Range Threshold Hysteresis. +Magnetometer 2 Y Axis throttle compensation. -This parameter defines the hysteresis for switching between short and long range mode. +Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 10 | | 1 | m | - -### SENS_AFBR_L_RATE (`INT32`) {#SENS_AFBR_L_RATE} +|   | | | | 0.0 | -AFBR Rangefinder Long Range Rate. +### CAL_MAG2_YODIAG (`FLOAT`) {#CAL_MAG2_YODIAG} -This parameter defines measurement rate of the AFBR Rangefinder in long range mode. +Magnetometer 2 Y-axis off diagonal scale factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 100 | | 25 | +|   | | | | 0.0 | -### SENS_AFBR_MODE (`INT32`) {#SENS_AFBR_MODE} +### CAL_MAG2_YOFF (`FLOAT`) {#CAL_MAG2_YOFF} -AFBR Rangefinder Mode. +Magnetometer 2 Y-axis offset. -This parameter defines the mode of the AFBR Rangefinder. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -**Values:** +### CAL_MAG2_YSCALE (`FLOAT`) {#CAL_MAG2_YSCALE} -- `0`: Short Range Mode -- `1`: Long Range Mode -- `2`: High Speed Short Range Mode -- `3`: High Speed Long Range Mode +Magnetometer 2 Y-axis scaling factor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 3 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -### SENS_AFBR_S_RATE (`INT32`) {#SENS_AFBR_S_RATE} +### CAL_MAG2_ZCOMP (`FLOAT`) {#CAL_MAG2_ZCOMP} -AFBR Rangefinder Short Range Rate. +Magnetometer 2 Z Axis throttle compensation. -This parameter defines measurement rate of the AFBR Rangefinder in short range mode. +Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 100 | | 50 | - -### SENS_AFBR_THRESH (`INT32`) {#SENS_AFBR_THRESH} +|   | | | | 0.0 | -AFBR Rangefinder Short/Long Range Threshold. +### CAL_MAG2_ZODIAG (`FLOAT`) {#CAL_MAG2_ZODIAG} -This parameter defines the threshold for switching between short and long range mode. -The mode will switch from short to long range when the distance is greater than the threshold plus the hysteresis. -The mode will switch from long to short range when the distance is less than the threshold minus the hysteresis. +Magnetometer 2 Z-axis off diagonal scale factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 50 | | 4 | m | +|   | | | | 0.0 | + +### CAL_MAG2_ZOFF (`FLOAT`) {#CAL_MAG2_ZOFF} + +Magnetometer 2 Z-axis offset. -### SENS_BAHRS_CFG (`INT32`) {#SENS_BAHRS_CFG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -Serial Configuration for EULER-NAV BAHRS. +### CAL_MAG2_ZSCALE (`FLOAT`) {#CAL_MAG2_ZSCALE} -Configure on which serial port to run EULER-NAV BAHRS. +Magnetometer 2 Z-axis scaling factor. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +### CAL_MAG3_ID (`INT32`) {#CAL_MAG3_ID} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +Magnetometer 3 calibration device ID. -### SENS_BARO_QNH (`FLOAT`) {#SENS_BARO_QNH} +Device ID of the magnetometer this calibration applies to. -QNH for barometer. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + +### CAL_MAG3_PITCH (`FLOAT`) {#CAL_MAG3_PITCH} + +Magnetometer 3 Custom Euler Pitch Angle. + +Setting this parameter changes CAL_MAG3_ROT to "Custom Euler Angle" | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 500 | 1500 | | 1013.25 | hPa | +|   | -180 | 180 | | 0.0 | deg | -### SENS_BARO_RATE (`FLOAT`) {#SENS_BARO_RATE} +### CAL_MAG3_PRIO (`INT32`) {#CAL_MAG3_PRIO} -Baro max rate. +Magnetometer 3 priority. -Barometric air data maximum publication rate. This is an upper bound, -actual barometric data rate is still dependent on the sensor. +**Values:** + +- `-1`: Uninitialized +- `0`: Disabled +- `1`: Min +- `25`: Low +- `50`: Medium (Default) +- `75`: High +- `100`: Max | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1 | 200 | | 20.0 | Hz | +|   | | | | -1 | -### SENS_BAR_AUTOCAL (`INT32`) {#SENS_BAR_AUTOCAL} +### CAL_MAG3_ROLL (`FLOAT`) {#CAL_MAG3_ROLL} -Barometer auto calibration. +Magnetometer 3 Custom Euler Roll Angle. -Automatically calibrate barometer based on the GNSS height +Setting this parameter changes CAL_MAG3_ROT to "Custom Euler Angle" -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -### SENS_BOARD_ROT (`INT32`) {#SENS_BOARD_ROT} +### CAL_MAG3_ROT (`INT32`) {#CAL_MAG3_ROT} -Board rotation. +Magnetometer 3 rotation relative to airframe. -This parameter defines the rotation of the FMU board relative to the platform. +An internal sensor will force a value of -1, so a GCS should only attempt to configure the rotation if the value is greater than or equal to zero. Set to "Custom Euler Angle" to define the rotation using CAL_MAG3_ROLL, CAL_MAG3_PITCH and CAL_MAG3_YAW. **Values:** +- `-1`: Internal - `0`: No rotation - `1`: Yaw 45° - `2`: Yaw 90° @@ -33472,897 +29741,729 @@ This parameter defines the rotation of the FMU board relative to the platform. - `38`: Roll 90°, Pitch 68°, Yaw 293° - `39`: Pitch 315° - `40`: Roll 90°, Pitch 315° - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | -1 | 40 | | 0 | - -### SENS_BOARD_X_OFF (`FLOAT`) {#SENS_BOARD_X_OFF} - -Board rotation X (roll) offset. - -Rotation from flight controller board to vehicle body frame. -This parameter gets set during the "level horizon" calibration or can be -set manually. +- `100`: Custom Euler Angle | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -45.0 | 45.0 | | 0.0 | deg | +|   | -1 | 100 | | -1 | -### SENS_BOARD_Y_OFF (`FLOAT`) {#SENS_BOARD_Y_OFF} +### CAL_MAG3_XCOMP (`FLOAT`) {#CAL_MAG3_XCOMP} -Board rotation Y (pitch) offset. +Magnetometer 3 X Axis throttle compensation. -Rotation from flight controller board to vehicle body frame. -This parameter gets set during the "level horizon" calibration or can be -set manually. +Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -45.0 | 45.0 | | 0.0 | deg | - -### SENS_BOARD_Z_OFF (`FLOAT`) {#SENS_BOARD_Z_OFF} +|   | | | | 0.0 | -Board rotation Z (yaw) offset. +### CAL_MAG3_XODIAG (`FLOAT`) {#CAL_MAG3_XODIAG} -Rotation from flight controller board to vehicle body frame. -Has to be set manually (not set by any calibration). +Magnetometer 3 X-axis off diagonal scale factor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -45.0 | 45.0 | | 0.0 | deg | - -### SENS_CM8JL65_CFG (`INT32`) {#SENS_CM8JL65_CFG} - -Serial Configuration for Lanbao PSK-CM8JL65-CC5. +|   | | | | 0.0 | -Configure on which serial port to run Lanbao PSK-CM8JL65-CC5. +### CAL_MAG3_XOFF (`FLOAT`) {#CAL_MAG3_XOFF} -**Values:** +Magnetometer 3 X-axis offset. -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +### CAL_MAG3_XSCALE (`FLOAT`) {#CAL_MAG3_XSCALE} -### SENS_CM8JL65_R_0 (`INT32`) {#SENS_CM8JL65_R_0} +Magnetometer 3 X-axis scaling factor. -Distance Sensor Rotation. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum +### CAL_MAG3_YAW (`FLOAT`) {#CAL_MAG3_YAW} -**Values:** +Magnetometer 3 Custom Euler Yaw Angle. -- `0`: ROTATION_FORWARD_FACING -- `2`: ROTATION_RIGHT_FACING -- `4`: ROTATION_BACKWARD_FACING -- `6`: ROTATION_LEFT_FACING -- `24`: ROTATION_UPWARD_FACING -- `25`: ROTATION_DOWNWARD_FACING +Setting this parameter changes CAL_MAG3_ROT to "Custom Euler Angle" -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 25 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -180 | 180 | | 0.0 | deg | -### SENS_EN_ADIS164X (`INT32`) {#SENS_EN_ADIS164X} +### CAL_MAG3_YCOMP (`FLOAT`) {#CAL_MAG3_YCOMP} -Analog Devices ADIS16448 IMU (external SPI). +Magnetometer 3 Y Axis throttle compensation. -**Values:** +Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -- `0`: Disabled -- `1`: Enabled +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +### CAL_MAG3_YODIAG (`FLOAT`) {#CAL_MAG3_YODIAG} -### SENS_EN_ADIS165X (`INT32`) {#SENS_EN_ADIS165X} +Magnetometer 3 Y-axis off diagonal scale factor. -Analog Devices ADIS16507 IMU (external SPI). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +### CAL_MAG3_YOFF (`FLOAT`) {#CAL_MAG3_YOFF} -### SENS_EN_AGPSIM (`INT32`) {#SENS_EN_AGPSIM} +Magnetometer 3 Y-axis offset. -Simulate Aux Global Position (AGP). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -**Values:** +### CAL_MAG3_YSCALE (`FLOAT`) {#CAL_MAG3_YSCALE} -- `0`: Disabled -- `1`: Enabled +Magnetometer 3 Y-axis scaling factor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -### SENS_EN_ARSPDSIM (`INT32`) {#SENS_EN_ARSPDSIM} +### CAL_MAG3_ZCOMP (`FLOAT`) {#CAL_MAG3_ZCOMP} -Enable simulated airspeed sensor instance. +Magnetometer 3 Z Axis throttle compensation. -**Values:** +Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP. Unit for throttle-based compensation is [G] and for current-based compensation [G/kA] -- `0`: Disabled -- `1`: Enabled +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +### CAL_MAG3_ZODIAG (`FLOAT`) {#CAL_MAG3_ZODIAG} -### SENS_EN_ASP5033 (`INT32`) {#SENS_EN_ASP5033} +Magnetometer 3 Z-axis off diagonal scale factor. -ASP5033 differential pressure sensor (external I2C). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +### CAL_MAG3_ZOFF (`FLOAT`) {#CAL_MAG3_ZOFF} -### SENS_EN_AUAVX (`INT32`) {#SENS_EN_AUAVX} +Magnetometer 3 Z-axis offset. -Amphenol AUAV differential / absolute pressure sensor (external I2C). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -**Values:** +### CAL_MAG3_ZSCALE (`FLOAT`) {#CAL_MAG3_ZSCALE} -- `0`: Sensor disabled, when explicitly started treated as AUAV L05D -- `1`: AUAV L05D -- `2`: AUAV L10D -- `3`: AUAV L30D +Magnetometer 3 Z-axis scaling factor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.1 | 3.0 | | 1.0 | -### SENS_EN_BAROSIM (`INT32`) {#SENS_EN_BAROSIM} +### CAL_MAG_COMP_TYP (`INT32`) {#CAL_MAG_COMP_TYP} -Enable simulated barometer sensor instance. +Type of magnetometer compensation. **Values:** - `0`: Disabled -- `1`: Enabled - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +- `1`: Throttle-based compensation +- `2`: Current-based compensation (battery_status instance 0) +- `3`: Current-based compensation (battery_status instance 1) -### SENS_EN_BATT (`INT32`) {#SENS_EN_BATT} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -SMBUS Smart battery driver BQ40Z50 and BQ40Z80. +### SENS_DPRES_ANSC (`FLOAT`) {#SENS_DPRES_ANSC} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +Differential pressure sensor analog scaling. -### SENS_EN_ETSASPD (`INT32`) {#SENS_EN_ETSASPD} +Pick the appropriate scaling from the datasheet. this number defines the (linear) conversion from voltage to Pascal (pa). For the MPXV7002DP this is 1000. NOTE: If the sensor always registers zero, try switching the static and dynamic tubes. -Eagle Tree airspeed sensor (external I2C). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +### SENS_DPRES_OFF (`FLOAT`) {#SENS_DPRES_OFF} -### SENS_EN_GPSSIM (`INT32`) {#SENS_EN_GPSSIM} +Differential pressure sensor offset. -Enable simulated GPS sinstance. +The offset (zero-reading) in Pascal -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | -- `0`: Disabled -- `1`: Enabled +### SENS_DPRES_REV (`INT32`) {#SENS_DPRES_REV} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +Reverse differential pressure sensor readings. -### SENS_EN_INA220 (`INT32`) {#SENS_EN_INA220} +Reverse the raw measurements of all differential pressure sensors. This can be enabled if the sensors have static and dynamic ports swapped. -Enable INA220 Power Monitor. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | -For systems a INA220 Power Monitor, this should be set to true +### SENS_FLOW_MAXHGT (`FLOAT`) {#SENS_FLOW_MAXHGT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +Maximum height above ground when reliant on optical flow. -### SENS_EN_INA226 (`INT32`) {#SENS_EN_INA226} +This parameter defines the maximum distance from ground at which the optical flow sensor operates reliably. The height setpoint will be limited to be no greater than this value when the navigation system is completely reliant on optical flow data and the height above ground estimate is valid. The sensor may be usable above this height, but accuracy will progressively degrade. -Enable INA226 Power Monitor. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1.0 | 100.0 | 0.1 | 100. | m | -For systems a INA226 Power Monitor, this should be set to true +### SENS_FLOW_MAXR (`FLOAT`) {#SENS_FLOW_MAXR} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +Magnitude of maximum angular flow rate reliably measurable by the optical flow sensor. -### SENS_EN_INA228 (`INT32`) {#SENS_EN_INA228} +Optical flow data will not fused by the estimators if the magnitude of the flow rate exceeds this value and control loops will be instructed to limit ground speed such that the flow rate produced by movement over ground is less than 50% of this value. -Enable INA228 Power Monitor. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | 1.0 | | | 8. | rad/s | -For systems a INA228 Power Monitor, this should be set to true +### SENS_FLOW_MINHGT (`FLOAT`) {#SENS_FLOW_MINHGT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +Minimum height above ground when reliant on optical flow. -### SENS_EN_INA238 (`INT32`) {#SENS_EN_INA238} +This parameter defines the minimum distance from ground at which the optical flow sensor operates reliably. The sensor may be usable below this height, but accuracy will progressively reduce to loss of focus. -Enable INA238 Power Monitor. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.0 | 1.0 | 0.1 | 0.08 | m | -For systems a INA238 Power Monitor, this should be set to true +## Sensors -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +### ADC_ADS1115_EN (`INT32`) {#ADC_ADS1115_EN} -### SENS_EN_IRLOCK (`INT32`) {#SENS_EN_IRLOCK} +Enable external ADS1115 ADC. -IR-LOCK Sensor (external I2C). +If enabled, the internal ADC is not used. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | | ✓ | | | | Disabled (0) | -### SENS_EN_LL40LS (`INT32`) {#SENS_EN_LL40LS} - -Lidar-Lite (LL40LS). - -**Values:** +### BAT1_C_MULT (`FLOAT`) {#BAT1_C_MULT} -- `0`: Disabled -- `1`: PWM -- `2`: I2C +Capacity/current multiplier for high-current capable SMBUS battery. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 2 | | 0 | +| ✓ | | | | 1.0 | -### SENS_EN_MAGSIM (`INT32`) {#SENS_EN_MAGSIM} +### BAT1_SMBUS_MODEL (`INT32`) {#BAT1_SMBUS_MODEL} -Enable simulated magnetometer sensor instance. +Battery device model. **Values:** -- `0`: Disabled -- `1`: Enabled +- `0`: AutoDetect +- `1`: BQ40Z50 based +- `2`: BQ40Z80 based | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | - -### SENS_EN_MB12XX (`INT32`) {#SENS_EN_MB12XX} - -Maxbotix Sonar (mb12xx). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| ✓ | 0 | 2 | | 0 | -### SENS_EN_MCP9808 (`INT32`) {#SENS_EN_MCP9808} +### BATMON_ADDR_DFLT (`INT32`) {#BATMON_ADDR_DFLT} -Enable MCP9808 temperature sensor (external I2C). +I2C address for BatMon battery 1. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 11 | -### SENS_EN_MPDT (`INT32`) {#SENS_EN_MPDT} +### BATMON_DRIVER_EN (`INT32`) {#BATMON_DRIVER_EN} -Enable Mappydot rangefinder (i2c). +Parameter to enable BatMon module. **Values:** - `0`: Disabled -- `1`: Autodetect +- `1`: Start on default I2C addr(BATMON_ADDR_DFLT) +- `2`: Autodetect I2C address (TODO) | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +| ✓ | 0 | 2 | | 0 | -### SENS_EN_MS4515 (`INT32`) {#SENS_EN_MS4515} +### CAL_AIR_CMODEL (`INT32`) {#CAL_AIR_CMODEL} -TE MS4515 differential pressure sensor (external I2C). +Airspeed sensor compensation model for the SDP3x. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +Model with Pitot CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Model without Pitot (1.5 mm tubes) CAL_AIR_TUBED_MM: Not used, 1.5 mm tubes assumed. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor. Tube Pressure Drop CAL_AIR_TUBED_MM: Diameter in mm of the pitot and tubes, must have the same diameter. CAL_AIR_TUBELEN: Length of the tubes connecting the pitot to the sensor and the static + dynamic port length of the pitot. -### SENS_EN_MS4525DO (`INT32`) {#SENS_EN_MS4525DO} +**Values:** -TE MS4525DO differential pressure sensor (external I2C). +- `0`: Model with Pitot +- `1`: Model without Pitot (1.5 mm tubes) +- `2`: Tube Pressure Drop -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -### SENS_EN_MS5525DS (`INT32`) {#SENS_EN_MS5525DS} +### CAL_AIR_TUBED_MM (`FLOAT`) {#CAL_AIR_TUBED_MM} -TE MS5525DSO differential pressure sensor (external I2C). +Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1.5 | 100 | | 1.5 | mm | -### SENS_EN_PAA3905 (`INT32`) {#SENS_EN_PAA3905} +### CAL_AIR_TUBELEN (`FLOAT`) {#CAL_AIR_TUBELEN} -PAA3905 Optical Flow. +Airspeed sensor tube length. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +See the CAL_AIR_CMODEL explanation on how this parameter should be set. -### SENS_EN_PAW3902 (`INT32`) {#SENS_EN_PAW3902} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.01 | 2.00 | | 0.2 | m | -PAW3902/PAW3903 Optical Flow. +### CAL_MAG_SIDES (`INT32`) {#CAL_MAG_SIDES} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +For legacy QGC support only. -### SENS_EN_PCF8583 (`INT32`) {#SENS_EN_PCF8583} +Use SENS_MAG_SIDES instead -PCF8583 eneable driver. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 63 | -Run PCF8583 driver automatically +### IMU_ACCEL_CUTOFF (`FLOAT`) {#IMU_ACCEL_CUTOFF} -**Values:** +Low pass filter cutoff frequency for accel. -- `0`: Disabled -- `1`: Eneabled +The cutoff frequency for the 2nd order butterworth filter on the primary accelerometer. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | - -### SENS_EN_PGA460 (`INT32`) {#SENS_EN_PGA460} - -PGA460 Ultrasonic driver (PGA460). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - -### SENS_EN_PMW3901 (`INT32`) {#SENS_EN_PMW3901} - -PMW3901 Optical Flow. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - -### SENS_EN_PX4FLOW (`INT32`) {#SENS_EN_PX4FLOW} - -PX4 Flow Optical Flow. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - -### SENS_EN_SCH16T (`INT32`) {#SENS_EN_SCH16T} +| ✓ | 0 | 1000 | | 30.0 | Hz | -Murata SCH16T IMU (external SPI). +### IMU_DGYRO_CUTOFF (`FLOAT`) {#IMU_DGYRO_CUTOFF} -**Values:** +Cutoff frequency for angular acceleration (D-Term filter). -- `0`: Disabled -- `1`: Enabled +The cutoff frequency for the 2nd order butterworth filter used on the time derivative of the measured angular velocity, also known as the D-term filter in the rate controller. The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to increase IMU_GYRO_CUTOFF, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | - -### SENS_EN_SDP3X (`INT32`) {#SENS_EN_SDP3X} +| ✓ | 0 | 1000 | 0.1 | 30.0 | Hz | -Sensirion SDP3X differential pressure sensor (external I2C). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - -### SENS_EN_SF0X (`INT32`) {#SENS_EN_SF0X} - -Lightware Laser Rangefinder hardware model (serial). - -**Values:** - -- `1`: SF02 -- `2`: SF10/a -- `3`: SF10/b -- `4`: SF10/c -- `5`: SF11/c -- `6`: SF30/b -- `7`: SF30/c -- `8`: LW20/c +### IMU_GYRO_CAL_EN (`INT32`) {#IMU_GYRO_CAL_EN} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1 | +IMU gyro auto calibration enable. -### SENS_EN_SF1XX (`INT32`) {#SENS_EN_SF1XX} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | -Lightware SF1xx/SF20/LW20 laser rangefinder (i2c). +### IMU_GYRO_CUTOFF (`FLOAT`) {#IMU_GYRO_CUTOFF} -**Values:** +Low pass filter cutoff frequency for gyro. -- `0`: Disabled -- `1`: SF10/a -- `2`: SF10/b -- `3`: SF10/c -- `4`: SF11/c -- `5`: SF/LW20/b -- `6`: SF/LW20/c -- `7`: SF/LW30/d +The cutoff frequency for the 2nd order butterworth filter on the primary gyro. This only affects the angular velocity sent to the controllers, not the estimators. It applies also to the angular acceleration (D-Term filter), see IMU_DGYRO_CUTOFF. A value of 0 disables the filter. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1000 | 0.1 | 40.0 | Hz | -### SENS_EN_SF45_CFG (`INT32`) {#SENS_EN_SF45_CFG} +### IMU_GYRO_DNF_BW (`FLOAT`) {#IMU_GYRO_DNF_BW} -Serial Configuration for Lightware SF45 Rangefinder (serial). +IMU gyro ESC notch filter bandwidth. -Configure on which serial port to run Lightware SF45 Rangefinder (serial). +Bandwidth per notch filter when using dynamic notch filtering with ESC RPM. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 5 | 30 | 0.1 | 15. | Hz | -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +### IMU_GYRO_DNF_EN (`INT32`) {#IMU_GYRO_DNF_EN} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +IMU gyro dynamic notch filtering. -### SENS_EN_SHT3X (`INT32`) {#SENS_EN_SHT3X} +Enable bank of dynamically updating notch filters. Requires ESC RPM feedback or onboard FFT (IMU_GYRO_FFT_EN). -SHT3x temperature and hygrometer. +**Bitmask:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +- `0`: ESC RPM +- `1`: FFT -### SENS_EN_SPA06 (`INT32`) {#SENS_EN_SPA06} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 3 | | 0 | -Goertek SPA06 Barometer (external I2C). +### IMU_GYRO_DNF_HMC (`INT32`) {#IMU_GYRO_DNF_HMC} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +IMU gyro dynamic notch filter harmonics. -### SENS_EN_SPL06 (`INT32`) {#SENS_EN_SPL06} +ESC RPM number of harmonics (multiples of RPM) for ESC RPM dynamic notch filtering. -Goertek SPL06 Barometer (external I2C). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 7 | | 3 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +### IMU_GYRO_DNF_MIN (`FLOAT`) {#IMU_GYRO_DNF_MIN} -### SENS_EN_SR05 (`INT32`) {#SENS_EN_SR05} +IMU gyro dynamic notch filter minimum frequency. -HY-SRF05 / HC-SR05. +Minimum notch filter frequency in Hz. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | 0.1 | 25. | Hz | -### SENS_EN_TF02PRO (`INT32`) {#SENS_EN_TF02PRO} +### IMU_GYRO_FFT_EN (`INT32`) {#IMU_GYRO_FFT_EN} -TF02 Pro Distance Sensor (i2c). +IMU gyro FFT enable. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | | ✓ | | | | Disabled (0) | -### SENS_EN_THERMAL (`INT32`) {#SENS_EN_THERMAL} +### IMU_GYRO_FFT_LEN (`INT32`) {#IMU_GYRO_FFT_LEN} -Thermal control of sensor temperature. +IMU gyro FFT length. **Values:** -- `-1`: Thermal control unavailable -- `0`: Thermal control off -- `1`: Thermal control enabled +- `256`: 256 +- `512`: 512 +- `1024`: 1024 +- `4096`: 4096 -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 512 | Hz | -### SENS_EN_TRANGER (`INT32`) {#SENS_EN_TRANGER} +### IMU_GYRO_FFT_MAX (`FLOAT`) {#IMU_GYRO_FFT_MAX} -TeraRanger Rangefinder (i2c). +IMU gyro FFT maximum frequency. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | 1000 | | 150. | Hz | -- `0`: Disabled -- `1`: Autodetect -- `2`: TROne -- `3`: TREvo60m -- `4`: TREvo600Hz -- `5`: TREvo3m +### IMU_GYRO_FFT_MIN (`FLOAT`) {#IMU_GYRO_FFT_MIN} + +IMU gyro FFT minimum frequency. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 3 | | 0 | +| ✓ | 1 | 1000 | | 30. | Hz | -### SENS_EN_VL53L0X (`INT32`) {#SENS_EN_VL53L0X} +### IMU_GYRO_FFT_SNR (`FLOAT`) {#IMU_GYRO_FFT_SNR} -VL53L0X Distance Sensor. +IMU gyro FFT SNR. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 30 | | 10. | -### SENS_EN_VL53L1X (`INT32`) {#SENS_EN_VL53L1X} +### IMU_GYRO_NF0_BW (`FLOAT`) {#IMU_GYRO_NF0_BW} -VL53L1X Distance Sensor. +Notch filter bandwidth for gyro. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF0_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. -### SENS_EXT_I2C_PRB (`INT32`) {#SENS_EXT_I2C_PRB} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 100 | 0.1 | 20.0 | Hz | -External I2C probe. +### IMU_GYRO_NF0_FRQ (`FLOAT`) {#IMU_GYRO_NF0_FRQ} -Probe for optional external I2C devices. +Notch filter frequency for gyro. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF0_BW" to set the bandwidth of the filter. A value of 0 disables the filter. -### SENS_FLOW_RATE (`FLOAT`) {#SENS_FLOW_RATE} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | 0.1 | 0.0 | Hz | -Optical flow max rate. +### IMU_GYRO_NF1_BW (`FLOAT`) {#IMU_GYRO_NF1_BW} + +Notch filter 1 bandwidth for gyro. -Optical flow data maximum publication rate. This is an upper bound, -actual optical flow data rate is still dependent on the sensor. +The frequency width of the stop band for the 2nd order notch filter on the primary gyro. See "IMU_GYRO_NF1_FRQ" to activate the filter and to set the notch frequency. Applies to both angular velocity and angular acceleration sent to the controllers. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 200 | | 70.0 | Hz | +| ✓ | 0 | 100 | 0.1 | 20.0 | Hz | -### SENS_FLOW_ROT (`INT32`) {#SENS_FLOW_ROT} +### IMU_GYRO_NF1_FRQ (`FLOAT`) {#IMU_GYRO_NF1_FRQ} -Optical flow rotation. +Notch filter 2 frequency for gyro. -This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. -Zero rotation is defined as X on flow board pointing towards front of vehicle. +The center frequency for the 2nd order notch filter on the primary gyro. This filter can be enabled to avoid feedback amplification of structural resonances at a specific frequency. This only affects the signal sent to the controllers, not the estimators. Applies to both angular velocity and angular acceleration sent to the controllers. See "IMU_GYRO_NF1_BW" to set the bandwidth of the filter. A value of 0 disables the filter. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1000 | 0.1 | 0.0 | Hz | -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +### IMU_GYRO_RATEMAX (`INT32`) {#IMU_GYRO_RATEMAX} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | +Gyro control data maximum publication rate (inner loop rate). -### SENS_FLOW_SCALE (`FLOAT`) {#SENS_FLOW_SCALE} +The maximum rate the gyro control data (vehicle_angular_velocity) will be allowed to publish at. This is the loop rate for the rate controller and outputs. Note: sensor data is always read and filtered at the full raw rate (eg commonly 8 kHz) regardless of this setting. -Optical flow scale factor. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.5 | 1.5 | | 1. | +- `100`: 100 Hz +- `250`: 250 Hz +- `400`: 400 Hz +- `800`: 800 Hz +- `1000`: 1000 Hz +- `2000`: 2000 Hz -### SENS_FTX_CFG (`INT32`) {#SENS_FTX_CFG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 100 | 2000 | | 400 | Hz | -Serial Configuration for FT Technologies Digital Wind Sensor (serial). +### IMU_INTEG_RATE (`INT32`) {#IMU_INTEG_RATE} -Configure on which serial port to run FT Technologies Digital Wind Sensor (serial). +IMU integration rate. + +The rate at which raw IMU data is integrated to produce delta angles and delta velocities. Recommended to set this to a multiple of the estimator update period (currently 10 ms for ekf2). **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `100`: 100 Hz +- `200`: 200 Hz +- `250`: 250 Hz +- `400`: 400 Hz | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 100 | 1000 | | 200 | Hz | -### SENS_GPS_MASK (`INT32`) {#SENS_GPS_MASK} +### INA220_CONFIG (`INT32`) {#INA220_CONFIG} -Multi GPS Blending Control Mask. +INA220 Power Monitor Config. -Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. -0 : Set to true to use speed accuracy -1 : Set to true to use horizontal position accuracy -2 : Set to true to use vertical position accuracy +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 65535 | 1 | 8607 | -**Bitmask:** +### INA220_CUR_BAT (`FLOAT`) {#INA220_CUR_BAT} -- `0`: use speed accuracy -- `1`: use hpos accuracy -- `2`: use vpos accuracy +INA220 Power Monitor Battery Max Current. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 7 | | 7 | - -### SENS_GPS_PRIME (`INT32`) {#SENS_GPS_PRIME} +|   | 0.1 | 500.0 | 0.1 | 164.0 | -Multi GPS primary instance. +### INA220_CUR_REG (`FLOAT`) {#INA220_CUR_REG} -When no blending is active, this defines the preferred GPS receiver instance. -The GPS selection logic waits until the primary receiver is available to -send data to the EKF even if a secondary instance is already available. -The secondary instance is then only used if the primary one times out. -To have an equal priority of all the instances, set this parameter to -1 and -the best receiver will be used. -This parameter has no effect if blending is active. +INA220 Power Monitor Regulator Max Current. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -1 | 1 | | 0 | - -### SENS_GPS_TAU (`FLOAT`) {#SENS_GPS_TAU} +|   | 0.1 | 500.0 | 0.1 | 164.0 | -Multi GPS Blending Time Constant. +### INA220_SHUNT_BAT (`FLOAT`) {#INA220_SHUNT_BAT} -Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences. +INA220 Power Monitor Battery Shunt. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 1.0 | 100.0 | | 10.0 | s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | ----------- | -------- | ---------- | ------- | ---- | +|   | 0.000000001 | 0.1 | .000000001 | 0.0005 | -### SENS_ILABS_CFG (`INT32`) {#SENS_ILABS_CFG} +### INA220_SHUNT_REG (`FLOAT`) {#INA220_SHUNT_REG} -Serial Configuration for InertialLabs. +INA220 Power Monitor Regulator Shunt. -Configure on which serial port to run InertialLabs. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | ----------- | -------- | ---------- | ------- | ---- | +|   | 0.000000001 | 0.1 | .000000001 | 0.0005 | -**Values:** +### INA226_CONFIG (`INT32`) {#INA226_CONFIG} -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +INA226 Power Monitor Config. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | - -### SENS_IMU_AUTOCAL (`INT32`) {#SENS_IMU_AUTOCAL} +| ✓ | 0 | 65535 | 1 | 18139 | -IMU auto calibration. +### INA226_CURRENT (`FLOAT`) {#INA226_CURRENT} -Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. +INA226 Power Monitor Max Current. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0.1 | 200.0 | 0.1 | 164.0 | -### SENS_IMU_CLPNOTI (`INT32`) {#SENS_IMU_CLPNOTI} +### INA226_SHUNT (`FLOAT`) {#INA226_SHUNT} -IMU notify clipping. +INA226 Power Monitor Shunt. -Notify the user if the IMU is clipping +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | ----------- | -------- | ---------- | ------- | ---- | +| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +### INA228_CONFIG (`INT32`) {#INA228_CONFIG} -### SENS_IMU_MODE (`INT32`) {#SENS_IMU_MODE} +INA228 Power Monitor Config. -Sensors hub IMU mode. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 65535 | 1 | 63779 | -**Values:** +### INA228_CURRENT (`FLOAT`) {#INA228_CURRENT} -- `0`: Disabled -- `1`: Publish primary IMU selection +INA228 Power Monitor Max Current. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1 | - -### SENS_IMU_TEMP (`FLOAT`) {#SENS_IMU_TEMP} +| ✓ | 0.1 | 327.68 | 0.1 | 327.68 | -Target IMU temperature. +### INA228_SHUNT (`FLOAT`) {#INA228_SHUNT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------- | -|   | 0 | 85.0 | | 55.0 | celcius | +INA228 Power Monitor Shunt. -### SENS_IMU_TEMP_FF (`FLOAT`) {#SENS_IMU_TEMP_FF} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | ----------- | -------- | ---------- | ------- | ---- | +| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | -IMU heater controller feedforward value. +### INA238_CURRENT (`FLOAT`) {#INA238_CURRENT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1.0 | | 0.05 | % | +INA238 Power Monitor Max Current. -### SENS_IMU_TEMP_I (`FLOAT`) {#SENS_IMU_TEMP_I} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0.1 | 327.68 | 0.1 | 327.68 | -IMU heater controller integrator gain value. +### INA238_SHUNT (`FLOAT`) {#INA238_SHUNT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1.0 | | 0.025 | us/C | +INA238 Power Monitor Shunt. -### SENS_IMU_TEMP_P (`FLOAT`) {#SENS_IMU_TEMP_P} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | ----------- | -------- | ---------- | ------- | ---- | +| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0005 | -IMU heater controller proportional gain value. +### PCF8583_MAGNET (`INT32`) {#PCF8583_MAGNET} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 2.0 | | 1.0 | us/C | +PCF8583 rotorfreq (i2c) pulse count. -### SENS_INT_BARO_EN (`INT32`) {#SENS_INT_BARO_EN} +Nmumber of signals per rotation of actuator -Enable internal barometers. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | | | 2 | -For systems with an external barometer, this should be set to false to make sure that the external is used. +### PCF8583_POOL (`INT32`) {#PCF8583_POOL} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +PCF8583 rotorfreq (i2c) pool interval. -### SENS_LEDDAR1_CFG (`INT32`) {#SENS_LEDDAR1_CFG} +Determines how often the sensor is read out. -Serial Configuration for LeddarOne Rangefinder. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 1000000 | us | -Configure on which serial port to run LeddarOne Rangefinder. +### PCF8583_RESET (`INT32`) {#PCF8583_RESET} -**Values:** +PCF8583 rotorfreq (i2c) pulse reset value. -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +Internal device counter is reset to 0 when overrun this value, counter is able to store up to 6 digits reset of counter takes some time - measurement with reset has worse accuracy. 0 means reset counter after every measurement. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | | | | 500000 | -### SENS_MAG_AUTOCAL (`INT32`) {#SENS_MAG_AUTOCAL} +### SENS_AFBR_HYSTER (`INT32`) {#SENS_AFBR_HYSTER} -Magnetometer auto calibration. +AFBR Rangefinder Short/Long Range Threshold Hysteresis. -Automatically initialize magnetometer calibration from bias estimate if available. +This parameter defines the hysteresis for switching between short and long range mode. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 10 | | 1 | m | -### SENS_MAG_AUTOROT (`INT32`) {#SENS_MAG_AUTOROT} +### SENS_AFBR_L_RATE (`INT32`) {#SENS_AFBR_L_RATE} -Automatically set external rotations. +AFBR Rangefinder Long Range Rate. -During calibration attempt to automatically determine the rotation of external magnetometers. +This parameter defines measurement rate of the AFBR Rangefinder in long range mode. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 100 | | 25 | -### SENS_MAG_MODE (`INT32`) {#SENS_MAG_MODE} +### SENS_AFBR_MODE (`INT32`) {#SENS_AFBR_MODE} -Sensors hub mag mode. +AFBR Rangefinder Mode. + +This parameter defines the mode of the AFBR Rangefinder. **Values:** -- `0`: Publish all magnetometers -- `1`: Publish primary magnetometer +- `0`: Short Range Mode +- `1`: Long Range Mode +- `2`: High Speed Short Range Mode +- `3`: High Speed Long Range Mode | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1 | +| ✓ | 0 | 3 | | 0 | -### SENS_MAG_RATE (`FLOAT`) {#SENS_MAG_RATE} +### SENS_AFBR_S_RATE (`INT32`) {#SENS_AFBR_S_RATE} -Magnetometer max rate. +AFBR Rangefinder Short Range Rate. -Magnetometer data maximum publication rate. This is an upper bound, -actual magnetometer data rate is still dependent on the sensor. +This parameter defines measurement rate of the AFBR Rangefinder in short range mode. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 200 | | 15.0 | Hz | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 100 | | 50 | -### SENS_MAG_SIDES (`INT32`) {#SENS_MAG_SIDES} +### SENS_AFBR_THRESH (`INT32`) {#SENS_AFBR_THRESH} -Bitfield selecting mag sides for calibration. +AFBR Rangefinder Short/Long Range Threshold. -If set to two side calibration, only the offsets are estimated, the scale -calibration is left unchanged. Thus an initial six side calibration is -recommended. -Bits: -ORIENTATION_TAIL_DOWN = 1 -ORIENTATION_NOSE_DOWN = 2 -ORIENTATION_LEFT = 4 -ORIENTATION_RIGHT = 8 -ORIENTATION_UPSIDE_DOWN = 16 -ORIENTATION_RIGHTSIDE_UP = 32 +This parameter defines the threshold for switching between short and long range mode. The mode will switch from short to long range when the distance is greater than the threshold plus the hysteresis. The mode will switch from long to short range when the distance is less than the threshold minus the hysteresis. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 50 | | 4 | m | -- `34`: Two side calibration -- `38`: Three side calibration -- `63`: Six side calibration +### SENS_BARO_QNH (`FLOAT`) {#SENS_BARO_QNH} + +QNH for barometer. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 34 | 63 | | 63 | +|   | 500 | 1500 | | 1013.25 | hPa | -### SENS_MB12_0_ROT (`INT32`) {#SENS_MB12_0_ROT} +### SENS_BARO_RATE (`FLOAT`) {#SENS_BARO_RATE} -MaxBotix MB12XX Sensor 0 Rotation. +Baro max rate. -This parameter defines the rotation of the sensor relative to the platform. +Barometric air data maximum publication rate. This is an upper bound, actual barometric data rate is still dependent on the sensor. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1 | 200 | | 20.0 | Hz | -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +### SENS_BAR_AUTOCAL (`INT32`) {#SENS_BAR_AUTOCAL} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +Barometer auto calibration. -### SENS_MB12_10_ROT (`INT32`) {#SENS_MB12_10_ROT} +Automatically calibrate barometer based on the GNSS height -MaxBotix MB12XX Sensor 10 Rotation. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------------ | ---- | +|   | | | | Disabled (0) | -This parameter defines the rotation of the sensor relative to the platform. +### SENS_BOARD_ROT (`INT32`) {#SENS_BOARD_ROT} + +Board rotation. + +This parameter defines the rotation of the FMU board relative to the platform. **Values:** @@ -34374,478 +30475,469 @@ This parameter defines the rotation of the sensor relative to the platform. - `5`: Yaw 225° - `6`: Yaw 270° - `7`: Yaw 315° +- `8`: Roll 180° +- `9`: Roll 180°, Yaw 45° +- `10`: Roll 180°, Yaw 90° +- `11`: Roll 180°, Yaw 135° +- `12`: Pitch 180° +- `13`: Roll 180°, Yaw 225° +- `14`: Roll 180°, Yaw 270° +- `15`: Roll 180°, Yaw 315° +- `16`: Roll 90° +- `17`: Roll 90°, Yaw 45° +- `18`: Roll 90°, Yaw 90° +- `19`: Roll 90°, Yaw 135° +- `20`: Roll 270° +- `21`: Roll 270°, Yaw 45° +- `22`: Roll 270°, Yaw 90° +- `23`: Roll 270°, Yaw 135° +- `24`: Pitch 90° +- `25`: Pitch 270° +- `26`: Pitch 180°, Yaw 90° +- `27`: Pitch 180°, Yaw 270° +- `28`: Roll 90°, Pitch 90° +- `29`: Roll 180°, Pitch 90° +- `30`: Roll 270°, Pitch 90° +- `31`: Roll 90°, Pitch 180° +- `32`: Roll 270°, Pitch 180° +- `33`: Roll 90°, Pitch 270° +- `34`: Roll 180°, Pitch 270° +- `35`: Roll 270°, Pitch 270° +- `36`: Roll 90°, Pitch 180°, Yaw 90° +- `37`: Roll 90°, Yaw 270° +- `38`: Roll 90°, Pitch 68°, Yaw 293° +- `39`: Pitch 315° +- `40`: Roll 90°, Pitch 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | -1 | 40 | | 0 | -### SENS_MB12_11_ROT (`INT32`) {#SENS_MB12_11_ROT} +### SENS_BOARD_X_OFF (`FLOAT`) {#SENS_BOARD_X_OFF} -MaxBotix MB12XX Sensor 12 Rotation. +Board rotation X (Roll) offset. -This parameter defines the rotation of the sensor relative to the platform. +This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user to fine tune the board offset in the event of misalignment. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | deg | + +### SENS_BOARD_Y_OFF (`FLOAT`) {#SENS_BOARD_Y_OFF} + +Board rotation Y (Pitch) offset. + +This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user to fine tune the board offset in the event of misalignment. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | deg | + +### SENS_BOARD_Z_OFF (`FLOAT`) {#SENS_BOARD_Z_OFF} + +Board rotation Z (YAW) offset. + +This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user to fine tune the board offset in the event of misalignment. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0.0 | deg | + +### SENS_CM8JL65_CFG (`INT32`) {#SENS_CM8JL65_CFG} + +Serial Configuration for Lanbao PSK-CM8JL65-CC5. + +Configure on which serial port to run Lanbao PSK-CM8JL65-CC5. **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | | | | 0 | -### SENS_MB12_1_ROT (`INT32`) {#SENS_MB12_1_ROT} +### SENS_CM8JL65_R_0 (`INT32`) {#SENS_CM8JL65_R_0} -MaxBotix MB12XX Sensor 1 Rotation. +Distance Sensor Rotation. -This parameter defines the rotation of the sensor relative to the platform. +Distance Sensor Rotation as MAV_SENSOR_ORIENTATION enum **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: ROTATION_FORWARD_FACING +- `2`: ROTATION_RIGHT_FACING +- `4`: ROTATION_BACKWARD_FACING +- `6`: ROTATION_LEFT_FACING +- `24`: ROTATION_UPWARD_FACING +- `25`: ROTATION_DOWNWARD_FACING | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | - -### SENS_MB12_2_ROT (`INT32`) {#SENS_MB12_2_ROT} +| ✓ | | | | 25 | -MaxBotix MB12XX Sensor 2 Rotation. +### SENS_EN_ADIS164X (`INT32`) {#SENS_EN_ADIS164X} -This parameter defines the rotation of the sensor relative to the platform. +Analog Devices ADIS16448 IMU (external SPI). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MB12_3_ROT (`INT32`) {#SENS_MB12_3_ROT} +### SENS_EN_ADIS165X (`INT32`) {#SENS_EN_ADIS165X} -MaxBotix MB12XX Sensor 3 Rotation. +Analog Devices ADIS16507 IMU (external SPI). -This parameter defines the rotation of the sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### SENS_EN_AGPSIM (`INT32`) {#SENS_EN_AGPSIM} + +Simulate Aux Global Position (AGP). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | - -### SENS_MB12_4_ROT (`INT32`) {#SENS_MB12_4_ROT} +| ✓ | 0 | 1 | | 0 | -MaxBotix MB12XX Sensor 4 Rotation. +### SENS_EN_ARSPDSIM (`INT32`) {#SENS_EN_ARSPDSIM} -This parameter defines the rotation of the sensor relative to the platform. +Enable simulated airspeed sensor instance. **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MB12_5_ROT (`INT32`) {#SENS_MB12_5_ROT} +### SENS_EN_ASP5033 (`INT32`) {#SENS_EN_ASP5033} -MaxBotix MB12XX Sensor 5 Rotation. +ASP5033 differential pressure sensor (external I2C). -This parameter defines the rotation of the sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### SENS_EN_AUAVX (`INT32`) {#SENS_EN_AUAVX} + +Amphenol AUAV differential / absolute pressure sensor (external I2C). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Sensor disabled, when explicitly started treated as AUAV L05D +- `1`: AUAV L05D +- `2`: AUAV L10D +- `3`: AUAV L30D | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | - -### SENS_MB12_6_ROT (`INT32`) {#SENS_MB12_6_ROT} +| ✓ | | | | 0 | -MaxBotix MB12XX Sensor 6 Rotation. +### SENS_EN_BAROSIM (`INT32`) {#SENS_EN_BAROSIM} -This parameter defines the rotation of the sensor relative to the platform. +Enable simulated barometer sensor instance. **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | - -### SENS_MB12_7_ROT (`INT32`) {#SENS_MB12_7_ROT} +| ✓ | 0 | 1 | | 0 | -MaxBotix MB12XX Sensor 7 Rotation. +### SENS_EN_BATT (`INT32`) {#SENS_EN_BATT} -This parameter defines the rotation of the sensor relative to the platform. +SMBUS Smart battery driver BQ40Z50 and BQ40Z80. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +### SENS_EN_ETSASPD (`INT32`) {#SENS_EN_ETSASPD} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +Eagle Tree airspeed sensor (external I2C). -### SENS_MB12_8_ROT (`INT32`) {#SENS_MB12_8_ROT} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -MaxBotix MB12XX Sensor 8 Rotation. +### SENS_EN_GPSSIM (`INT32`) {#SENS_EN_GPSSIM} -This parameter defines the rotation of the sensor relative to the platform. +Enable simulated GPS sinstance. **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MB12_9_ROT (`INT32`) {#SENS_MB12_9_ROT} +### SENS_EN_INA220 (`INT32`) {#SENS_EN_INA220} -MaxBotix MB12XX Sensor 9 Rotation. +Enable INA220 Power Monitor. -This parameter defines the rotation of the sensor relative to the platform. +For systems a INA220 Power Monitor, this should be set to true -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +### SENS_EN_INA226 (`INT32`) {#SENS_EN_INA226} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +Enable INA226 Power Monitor. -### SENS_MPDT0_ROT (`INT32`) {#SENS_MPDT0_ROT} +For systems a INA226 Power Monitor, this should be set to true -MappyDot Sensor 0 Rotation. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -This parameter defines the rotation of the Mappydot sensor relative to the platform. +### SENS_EN_INA228 (`INT32`) {#SENS_EN_INA228} -**Values:** +Enable INA228 Power Monitor. -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +For systems a INA228 Power Monitor, this should be set to true -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -### SENS_MPDT10_ROT (`INT32`) {#SENS_MPDT10_ROT} +### SENS_EN_INA238 (`INT32`) {#SENS_EN_INA238} -MappyDot Sensor 10 Rotation. +Enable INA238 Power Monitor. -This parameter defines the rotation of the Mappydot sensor relative to the platform. +For systems a INA238 Power Monitor, this should be set to true -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +### SENS_EN_IRLOCK (`INT32`) {#SENS_EN_IRLOCK} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +IR-LOCK Sensor (external I2C). -### SENS_MPDT11_ROT (`INT32`) {#SENS_MPDT11_ROT} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -MappyDot Sensor 12 Rotation. +### SENS_EN_LL40LS (`INT32`) {#SENS_EN_LL40LS} -This parameter defines the rotation of the Mappydot sensor relative to the platform. +Lidar-Lite (LL40LS). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: PWM +- `2`: I2C | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | - -### SENS_MPDT1_ROT (`INT32`) {#SENS_MPDT1_ROT} +| ✓ | 0 | 2 | | 0 | -MappyDot Sensor 1 Rotation. +### SENS_EN_MAGSIM (`INT32`) {#SENS_EN_MAGSIM} -This parameter defines the rotation of the Mappydot sensor relative to the platform. +Enable simulated magnetometer sensor instance. **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MPDT2_ROT (`INT32`) {#SENS_MPDT2_ROT} +### SENS_EN_MB12XX (`INT32`) {#SENS_EN_MB12XX} -MappyDot Sensor 2 Rotation. +Maxbotix Sonar (mb12xx). -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### SENS_EN_MPDT (`INT32`) {#SENS_EN_MPDT} + +Enable Mappydot rangefinder (i2c). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Autodetect | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MPDT3_ROT (`INT32`) {#SENS_MPDT3_ROT} +### SENS_EN_MS4515 (`INT32`) {#SENS_EN_MS4515} -MappyDot Sensor 3 Rotation. +TE MS4515 differential pressure sensor (external I2C). -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -**Values:** +### SENS_EN_MS4525DO (`INT32`) {#SENS_EN_MS4525DO} -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +TE MS4525DO differential pressure sensor (external I2C). -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -### SENS_MPDT4_ROT (`INT32`) {#SENS_MPDT4_ROT} +### SENS_EN_MS5525DS (`INT32`) {#SENS_EN_MS5525DS} -MappyDot Sensor 4 Rotation. +TE MS5525DSO differential pressure sensor (external I2C). -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -**Values:** +### SENS_EN_PAA3905 (`INT32`) {#SENS_EN_PAA3905} -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +PAA3905 Optical Flow. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -### SENS_MPDT5_ROT (`INT32`) {#SENS_MPDT5_ROT} +### SENS_EN_PAW3902 (`INT32`) {#SENS_EN_PAW3902} -MappyDot Sensor 5 Rotation. +PAW3902/PAW3903 Optical Flow. -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### SENS_EN_PCF8583 (`INT32`) {#SENS_EN_PCF8583} + +PCF8583 eneable driver. + +Run PCF8583 driver automatically **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Eneabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MPDT6_ROT (`INT32`) {#SENS_MPDT6_ROT} +### SENS_EN_PGA460 (`INT32`) {#SENS_EN_PGA460} -MappyDot Sensor 6 Rotation. +PGA460 Ultrasonic driver (PGA460). -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -**Values:** +### SENS_EN_PMW3901 (`INT32`) {#SENS_EN_PMW3901} -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +PMW3901 Optical Flow. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -### SENS_MPDT7_ROT (`INT32`) {#SENS_MPDT7_ROT} +### SENS_EN_PX4FLOW (`INT32`) {#SENS_EN_PX4FLOW} -MappyDot Sensor 7 Rotation. +PX4 Flow Optical Flow. -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### SENS_EN_SCH16T (`INT32`) {#SENS_EN_SCH16T} + +Murata SCH16T IMU (external SPI). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: Enabled | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 1 | | 0 | -### SENS_MPDT8_ROT (`INT32`) {#SENS_MPDT8_ROT} +### SENS_EN_SDP3X (`INT32`) {#SENS_EN_SDP3X} -MappyDot Sensor 8 Rotation. +Sensirion SDP3X differential pressure sensor (external I2C). -This parameter defines the rotation of the Mappydot sensor relative to the platform. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | + +### SENS_EN_SF0X (`INT32`) {#SENS_EN_SF0X} + +Lightware Laser Rangefinder hardware model (serial). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `1`: SF02 +- `2`: SF10/a +- `3`: SF10/b +- `4`: SF10/c +- `5`: SF11/c +- `6`: SF30/b +- `7`: SF30/c +- `8`: LW20/c | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | - -### SENS_MPDT9_ROT (`INT32`) {#SENS_MPDT9_ROT} +| ✓ | | | | 1 | -MappyDot Sensor 9 Rotation. +### SENS_EN_SF1XX (`INT32`) {#SENS_EN_SF1XX} -This parameter defines the rotation of the Mappydot sensor relative to the platform. +Lightware SF1xx/SF20/LW20 laser rangefinder (i2c). **Values:** -- `0`: No rotation -- `1`: Yaw 45° -- `2`: Yaw 90° -- `3`: Yaw 135° -- `4`: Yaw 180° -- `5`: Yaw 225° -- `6`: Yaw 270° -- `7`: Yaw 315° +- `0`: Disabled +- `1`: SF10/a +- `2`: SF10/b +- `3`: SF10/c +- `4`: SF11/c +- `5`: SF/LW20/b +- `6`: SF/LW20/c +- `7`: SF/LW30/d | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 7 | | 0 | +| ✓ | 0 | 6 | | 0 | -### SENS_MS_CFG (`INT32`) {#SENS_MS_CFG} +### SENS_EN_SF45_CFG (`INT32`) {#SENS_EN_SF45_CFG} -Serial Configuration for MICROSTRAIN. +Serial Configuration for Lightware SF45 Rangefinder (serial). -Configure on which serial port to run MICROSTRAIN. +Configure on which serial port to run Lightware SF45 Rangefinder (serial). **Values:** @@ -34866,173 +30958,147 @@ Configure on which serial port to run MICROSTRAIN. | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 0 | -### SENS_OR_ADIS164X (`INT32`) {#SENS_OR_ADIS164X} +### SENS_EN_SHT3X (`INT32`) {#SENS_EN_SHT3X} -Analog Devices ADIS16448 IMU Orientation(external SPI). +SHT3x temperature and hygrometer. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -- `0`: ROTATION_NONE -- `4`: ROTATION_YAW_180 +### SENS_EN_SPA06 (`INT32`) {#SENS_EN_SPA06} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 101 | | 0 | +Goertek SPA06 Barometer (external I2C). -### SENS_SBG_CFG (`INT32`) {#SENS_SBG_CFG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -Serial Configuration for sbgECom. +### SENS_EN_SPL06 (`INT32`) {#SENS_EN_SPL06} -Configure on which serial port to run sbgECom. +Goertek SPL06 Barometer (external I2C). -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +### SENS_EN_SR05 (`INT32`) {#SENS_EN_SR05} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +HY-SRF05 / HC-SR05. -### SENS_SF0X_CFG (`INT32`) {#SENS_SF0X_CFG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -Serial Configuration for Lightware Laser Rangefinder (serial). +### SENS_EN_TF02PRO (`INT32`) {#SENS_EN_TF02PRO} -Configure on which serial port to run Lightware Laser Rangefinder (serial). +TF02 Pro Distance Sensor (i2c). -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +### SENS_EN_THERMAL (`INT32`) {#SENS_EN_THERMAL} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +Thermal control of sensor temperature. -### SENS_TEMP_ID (`INT32`) {#SENS_TEMP_ID} +**Values:** -Target IMU device ID to regulate temperature. +- `-1`: Thermal control unavailable +- `0`: Thermal control off +- `1`: Thermal control enabled | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### SENS_TFLOW_CFG (`INT32`) {#SENS_TFLOW_CFG} +|   | | | | -1 | -Serial Configuration for ThoneFlow-3901U optical flow sensor. +### SENS_EN_TRANGER (`INT32`) {#SENS_EN_TRANGER} -Configure on which serial port to run ThoneFlow-3901U optical flow sensor. +TeraRanger Rangefinder (i2c). **Values:** - `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `1`: Autodetect +- `2`: TROne +- `3`: TREvo60m +- `4`: TREvo600Hz +- `5`: TREvo3m | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 3 | | 0 | -### SENS_TFMINI_CFG (`INT32`) {#SENS_TFMINI_CFG} +### SENS_EN_VL53L0X (`INT32`) {#SENS_EN_VL53L0X} -Serial Configuration for Benewake TFmini Rangefinder. +VL53L0X Distance Sensor. -Configure on which serial port to run Benewake TFmini Rangefinder. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -**Values:** +### SENS_EN_VL53L1X (`INT32`) {#SENS_EN_VL53L1X} -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +VL53L1X Distance Sensor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -### SENS_TFMINI_HW (`INT32`) {#SENS_TFMINI_HW} +### SENS_EXT_I2C_PRB (`INT32`) {#SENS_EXT_I2C_PRB} -Hardware Model. +External I2C probe. -Models differ in range and FoV. +Probe for optional external I2C devices. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | -- `1`: TFMINI -- `2`: ISTRA24 -- `3`: ISTRA24_100m +### SENS_FLOW_RATE (`FLOAT`) {#SENS_FLOW_RATE} + +Optical flow max rate. + +Optical flow data maximum publication rate. This is an upper bound, actual optical flow data rate is still dependent on the sensor. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 3 | | 1 | +| ✓ | 1 | 200 | | 70.0 | Hz | -### SENS_ULAND_CFG (`INT32`) {#SENS_ULAND_CFG} +### SENS_FLOW_ROT (`INT32`) {#SENS_FLOW_ROT} -Serial Configuration for uLanding Radar. +Optical flow rotation. -Configure on which serial port to run uLanding Radar. +This parameter defines the yaw rotation of the optical flow relative to the vehicle body frame. Zero rotation is defined as X on flow board pointing towards front of vehicle. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -### SENS_VN_CFG (`INT32`) {#SENS_VN_CFG} +### SENS_FLOW_SCALE (`FLOAT`) {#SENS_FLOW_SCALE} -Serial Configuration for VectorNav (VN-100, VN-200, VN-300). +Optical flow scale factor. -Configure on which serial port to run VectorNav (VN-100, VN-200, VN-300). +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0.5 | 1.5 | | 1. | + +### SENS_FTX_CFG (`INT32`) {#SENS_FTX_CFG} + +Serial Configuration for FT Technologies Digital Wind Sensor (serial). + +Configure on which serial port to run FT Technologies Digital Wind Sensor (serial). **Values:** @@ -35053,1945 +31119,2056 @@ Configure on which serial port to run VectorNav (VN-100, VN-200, VN-300). | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 0 | -### SF45_ORIENT_CFG (`INT32`) {#SF45_ORIENT_CFG} +### SENS_GPS_MASK (`INT32`) {#SENS_GPS_MASK} -Orientation upright or facing downward. +Multi GPS Blending Control Mask. -The SF45 mounted facing upward or downward on the frame +Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy -**Values:** +**Bitmask:** -- `24`: Rotation upward -- `25`: Rotation downward +- `0`: use speed accuracy +- `1`: use hpos accuracy +- `2`: use vpos accuracy -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 24 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 7 | | 7 | -### SF45_UPDATE_CFG (`INT32`) {#SF45_UPDATE_CFG} +### SENS_GPS_PRIME (`INT32`) {#SENS_GPS_PRIME} -Update rate in Hz. +Multi GPS primary instance. -The SF45 sets the update rate in Hz to allow greater resolution +When no blending is active, this defines the preferred GPS receiver instance. The GPS selection logic waits until the primary receiver is available to send data to the EKF even if a secondary instance is already available. The secondary instance is then only used if the primary one times out. To have an equal priority of all the instances, set this parameter to -1 and the best receiver will be used. This parameter has no effect if blending is active. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | -1 | 1 | | 0 | -- `1`: 50hz -- `2`: 100hz -- `3`: 200hz -- `4`: 400hz -- `5`: 500hz -- `6`: 625hz -- `7`: 1000hz -- `8`: 1250hz -- `9`: 1538hz -- `10`: 2000hz -- `11`: 2500hz -- `12`: 5000hz +### SENS_GPS_TAU (`FLOAT`) {#SENS_GPS_TAU} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 5 | +Multi GPS Blending Time Constant. -### SF45_YAW_CFG (`INT32`) {#SF45_YAW_CFG} +Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences. -Sensor facing forward or backward. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 1.0 | 100.0 | | 10.0 | s | -The usb port on the sensor indicates 180deg, opposite usb is forward facing +### SENS_IMU_AUTOCAL (`INT32`) {#SENS_IMU_AUTOCAL} -**Values:** +IMU auto calibration. -- `0`: Rotation forward -- `2`: Rotation right -- `4`: Rotation backward -- `6`: Rotation left +Automatically initialize IMU (accel/gyro) calibration from bias estimates if available. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | -### SIM_ARSPD_FAIL (`INT32`) {#SIM_ARSPD_FAIL} +### SENS_IMU_CLPNOTI (`INT32`) {#SENS_IMU_CLPNOTI} -Dynamically simulate failure of airspeed sensor instance. +IMU notify clipping. + +Notify the user if the IMU is clipping + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | + +### SENS_IMU_MODE (`INT32`) {#SENS_IMU_MODE} + +Sensors hub IMU mode. **Values:** - `0`: Disabled -- `1`: Enabled +- `1`: Publish primary IMU selection | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +| ✓ | | | | 1 | -### VN_MODE (`INT32`) {#VN_MODE} +### SENS_IMU_TEMP (`FLOAT`) {#SENS_IMU_TEMP} -VectorNav driver mode. +Target IMU temperature. -INS or sensors +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------- | +|   | 0 | 85.0 | | 55.0 | celcius | -**Values:** +### SENS_IMU_TEMP_FF (`FLOAT`) {#SENS_IMU_TEMP_FF} -- `0`: Sensors Only (default) -- `1`: INS +IMU heater controller feedforward value. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0 | - -### VOXLPM_SHUNT_BAT (`FLOAT`) {#VOXLPM_SHUNT_BAT} +|   | 0 | 1.0 | | 0.05 | % | -VOXL Power Monitor Shunt, Battery. +### SENS_IMU_TEMP_I (`FLOAT`) {#SENS_IMU_TEMP_I} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | ----------- | -------- | ---------- | ------- | ---- | -| ✓ | 0.000000001 | 0.1 | .000000001 | 0.00063 | +IMU heater controller integrator gain value. -### VOXLPM_SHUNT_REG (`FLOAT`) {#VOXLPM_SHUNT_REG} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 1.0 | | 0.025 | us/C | -VOXL Power Monitor Shunt, Regulator. +### SENS_IMU_TEMP_P (`FLOAT`) {#SENS_IMU_TEMP_P} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | ----------- | -------- | ---------- | ------- | ---- | -| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0056 | +IMU heater controller proportional gain value. -## Septentrio +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 0 | 2.0 | | 1.0 | us/C | -### SEP_AUTO_CONFIG (`INT32`) {#SEP_AUTO_CONFIG} +### SENS_INT_BARO_EN (`INT32`) {#SENS_INT_BARO_EN} -Toggle automatic receiver configuration. +Enable internal barometers. -By default, the receiver is automatically configured. Sometimes it may be used for multiple purposes. -If the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration. -A good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments. +For systems with an external barometer, this should be set to false to make sure that the external is used. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | | ✓ | | | | Enabled (1) | -### SEP_CONST_USAGE (`INT32`) {#SEP_CONST_USAGE} +### SENS_LEDDAR1_CFG (`INT32`) {#SENS_LEDDAR1_CFG} -Usage of different constellations. +Serial Configuration for LeddarOne Rangefinder. -Choice of which constellations the receiver should use for PVT computation. -When this is 0, the constellation usage isn't changed. +Configure on which serial port to run LeddarOne Rangefinder. -**Bitmask:** +**Values:** -- `0`: GPS -- `1`: GLONASS -- `2`: Galileo -- `3`: SBAS -- `4`: BeiDou +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 63 | | 0 | +| ✓ | | | | 0 | -### SEP_DUMP_COMM (`INT32`) {#SEP_DUMP_COMM} +### SENS_MAG_AUTOCAL (`INT32`) {#SENS_MAG_AUTOCAL} -Log GPS communication data. +Magnetometer auto calibration. -Log raw communication between the driver and connected receivers. -For example, "To receiver" will log all commands and corrections sent by the driver to the receiver. +Automatically initialize magnetometer calibration from bias estimate if available. -**Values:** +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | -- `0`: Disabled -- `1`: From receiver -- `2`: To receiver -- `3`: Both +### SENS_MAG_AUTOROT (`INT32`) {#SENS_MAG_AUTOROT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 3 | | 0 | +Automatically set external rotations. -### SEP_HARDW_SETUP (`INT32`) {#SEP_HARDW_SETUP} +During calibration attempt to automatically determine the rotation of external magnetometers. -Setup and expected use of the hardware. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ----------- | ---- | +|   | | | | Enabled (1) | + +### SENS_MAG_MODE (`INT32`) {#SENS_MAG_MODE} -- Default: Use two receivers as completely separate instances. -- Moving base: Use two receivers in a rover & moving base setup for heading. +Sensors hub mag mode. **Values:** -- `0`: Default -- `1`: Moving base +- `0`: Publish all magnetometers +- `1`: Publish primary magnetometer | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 1 | | 0 | +| ✓ | | | | 1 | -### SEP_LOG_FORCE (`INT32`) {#SEP_LOG_FORCE} +### SENS_MAG_RATE (`FLOAT`) {#SENS_MAG_RATE} -Whether to overwrite or add to existing logging. +Magnetometer max rate. -When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data. +Magnetometer data maximum publication rate. This is an upper bound, actual magnetometer data rate is still dependent on the sensor. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | 200 | | 15.0 | Hz | -### SEP_LOG_HZ (`INT32`) {#SEP_LOG_HZ} +### SENS_MAG_SIDES (`INT32`) {#SENS_MAG_SIDES} -Logging frequency for the receiver. +Bitfield selecting mag sides for calibration. -Select the frequency at which the connected receiver should log data to its internal storage. +If set to two side calibration, only the offsets are estimated, the scale calibration is left unchanged. Thus an initial six side calibration is recommended. Bits: ORIENTATION_TAIL_DOWN = 1 ORIENTATION_NOSE_DOWN = 2 ORIENTATION_LEFT = 4 ORIENTATION_RIGHT = 8 ORIENTATION_UPSIDE_DOWN = 16 ORIENTATION_RIGHTSIDE_UP = 32 **Values:** -- `0`: Disabled -- `1`: 0.1 Hz -- `2`: 0.2 Hz -- `3`: 0.5 Hz -- `4`: 1 Hz -- `5`: 2 Hz -- `6`: 5 Hz -- `7`: 10 Hz -- `8`: 20 Hz -- `9`: 25 Hz -- `10`: 50 Hz +- `34`: Two side calibration +- `38`: Three side calibration +- `63`: Six side calibration -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 10 | | 0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | 34 | 63 | | 63 | -### SEP_LOG_LEVEL (`INT32`) {#SEP_LOG_LEVEL} +### SENS_MB12_0_ROT (`INT32`) {#SENS_MB12_0_ROT} -Logging level for the receiver. +MaxBotix MB12XX Sensor 0 Rotation. -Select the level of detail that needs to be logged by the receiver. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Lite -- `1`: Basic -- `2`: Default -- `3`: Full +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 3 | | 2 | +| ✓ | 0 | 7 | | 0 | -### SEP_OUTP_HZ (`INT32`) {#SEP_OUTP_HZ} +### SENS_MB12_10_ROT (`INT32`) {#SENS_MB12_10_ROT} -Output frequency of main SBF blocks. +MaxBotix MB12XX Sensor 10 Rotation. -The output frequency of the main SBF blocks needed for PVT information. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: 5 Hz -- `1`: 10 Hz -- `2`: 20 Hz -- `3`: 25 Hz +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 3 | | 1 | +| ✓ | 0 | 7 | | 0 | -### SEP_PITCH_OFFS (`FLOAT`) {#SEP_PITCH_OFFS} +### SENS_MB12_11_ROT (`INT32`) {#SENS_MB12_11_ROT} -Pitch offset for dual antenna GPS. +MaxBotix MB12XX Sensor 12 Rotation. + +This parameter defines the rotation of the sensor relative to the platform. + +**Values:** -Vertical offsets can be compensated for by adjusting the Pitch offset. -Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. -This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. -Since pitch is defined as the right-handed rotation about the vehicle Y axis, -a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch. +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | -90 | 90 | | 0 | deg | +| ✓ | 0 | 7 | | 0 | -### SEP_PORT1_CFG (`INT32`) {#SEP_PORT1_CFG} +### SENS_MB12_1_ROT (`INT32`) {#SENS_MB12_1_ROT} -Serial Configuration for GPS Port. +MaxBotix MB12XX Sensor 1 Rotation. -Configure on which serial port to run GPS Port. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SEP_PORT2_CFG (`INT32`) {#SEP_PORT2_CFG} +### SENS_MB12_2_ROT (`INT32`) {#SENS_MB12_2_ROT} -Serial Configuration for Secondary GPS port. +MaxBotix MB12XX Sensor 2 Rotation. -Configure on which serial port to run Secondary GPS port. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SEP_SAT_INFO (`INT32`) {#SEP_SAT_INFO} +### SENS_MB12_3_ROT (`INT32`) {#SENS_MB12_3_ROT} -Enable sat info. +MaxBotix MB12XX Sensor 3 Rotation. -Enable publication of satellite info (ORB_ID(satellite_info)) if possible. +This parameter defines the rotation of the sensor relative to the platform. -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +**Values:** -### SEP_STREAM_LOG (`INT32`) {#SEP_STREAM_LOG} +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° -Logging stream used during automatic configuration. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 7 | | 0 | + +### SENS_MB12_4_ROT (`INT32`) {#SENS_MB12_4_ROT} + +MaxBotix MB12XX Sensor 4 Rotation. -The stream the autopilot sets up on the receiver to output the logging data. -Set this to another value if the default stream is already used for another purpose. +This parameter defines the rotation of the sensor relative to the platform. + +**Values:** + +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 10 | | 2 | - -### SEP_STREAM_MAIN (`INT32`) {#SEP_STREAM_MAIN} - -Main stream used during automatic configuration. +| ✓ | 0 | 7 | | 0 | -The stream the autopilot sets up on the receiver to output the main data. -Set this to another value if the default stream is already used for another purpose. +### SENS_MB12_5_ROT (`INT32`) {#SENS_MB12_5_ROT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 1 | 10 | | 1 | +MaxBotix MB12XX Sensor 5 Rotation. -### SEP_YAW_OFFS (`FLOAT`) {#SEP_YAW_OFFS} +This parameter defines the rotation of the sensor relative to the platform. -Heading/Yaw offset for dual antenna GPS. +**Values:** -Heading offset angle for dual antenna GPS setups that support heading estimation. -Set this to 0 if the antennas are parallel to the forward-facing direction -of the vehicle and the rover antenna is in front. -The offset angle increases clockwise. -Set this to 90 if the rover antenna is placed on the -right side of the vehicle and the moving base antenna is on the left side. +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | -360 | 360 | | 0 | deg | - -## Serial +| ✓ | 0 | 7 | | 0 | -### RC_CRSF_PRT_CFG (`INT32`) {#RC_CRSF_PRT_CFG} +### SENS_MB12_6_ROT (`INT32`) {#SENS_MB12_6_ROT} -Serial Configuration for CRSF RC Input Driver. +MaxBotix MB12XX Sensor 6 Rotation. -Configure on which serial port to run CRSF RC Input Driver. -Crossfire RC (CRSF) driver. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### RC_DSM_PRT_CFG (`INT32`) {#RC_DSM_PRT_CFG} +### SENS_MB12_7_ROT (`INT32`) {#SENS_MB12_7_ROT} -Serial Configuration for DSM RC Input Driver. +MaxBotix MB12XX Sensor 7 Rotation. -Configure on which serial port to run DSM RC Input Driver. -DSM RC (Spektrum) driver. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### RC_GHST_PRT_CFG (`INT32`) {#RC_GHST_PRT_CFG} +### SENS_MB12_8_ROT (`INT32`) {#SENS_MB12_8_ROT} -Serial Configuration for GHST RC Input Driver. +MaxBotix MB12XX Sensor 8 Rotation. -Configure on which serial port to run GHST RC Input Driver. -Ghost (GHST) RC driver. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### RC_PORT_CONFIG (`INT32`) {#RC_PORT_CONFIG} +### SENS_MB12_9_ROT (`INT32`) {#SENS_MB12_9_ROT} -Serial Configuration for RC Input Driver. +MaxBotix MB12XX Sensor 9 Rotation. -Configure on which serial port to run RC Input Driver. -Setting this to 'Disabled' will use a board-specific default port for RC input. +This parameter defines the rotation of the sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 300 | +| ✓ | 0 | 7 | | 0 | -### RC_SBUS_PRT_CFG (`INT32`) {#RC_SBUS_PRT_CFG} +### SENS_MPDT0_ROT (`INT32`) {#SENS_MPDT0_ROT} -Serial Configuration for SBUS RC Input Driver. +MappyDot Sensor 0 Rotation. -Configure on which serial port to run SBUS RC Input Driver. -SBUS RC driver. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Disabled -- `6`: UART 6 -- `101`: TELEM 1 -- `102`: TELEM 2 -- `103`: TELEM 3 -- `104`: TELEM/SERIAL 4 -- `201`: GPS 1 -- `202`: GPS 2 -- `203`: GPS 3 -- `300`: Radio Controller -- `301`: Wifi Port -- `401`: EXT2 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SER_EXT2_BAUD (`INT32`) {#SER_EXT2_BAUD} +### SENS_MPDT10_ROT (`INT32`) {#SENS_MPDT10_ROT} -Baudrate for the EXT2 Serial Port. +MappyDot Sensor 10 Rotation. -Configure the Baudrate for the EXT2 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 57600 | +| ✓ | 0 | 7 | | 0 | -### SER_GPS1_BAUD (`INT32`) {#SER_GPS1_BAUD} +### SENS_MPDT11_ROT (`INT32`) {#SENS_MPDT11_ROT} -Baudrate for the GPS 1 Serial Port. +MappyDot Sensor 12 Rotation. -Configure the Baudrate for the GPS 1 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SER_GPS2_BAUD (`INT32`) {#SER_GPS2_BAUD} +### SENS_MPDT1_ROT (`INT32`) {#SENS_MPDT1_ROT} -Baudrate for the GPS 2 Serial Port. +MappyDot Sensor 1 Rotation. -Configure the Baudrate for the GPS 2 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SER_GPS3_BAUD (`INT32`) {#SER_GPS3_BAUD} +### SENS_MPDT2_ROT (`INT32`) {#SENS_MPDT2_ROT} -Baudrate for the GPS 3 Serial Port. +MappyDot Sensor 2 Rotation. -Configure the Baudrate for the GPS 3 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SER_MXS_BAUD (`INT32`) {#SER_MXS_BAUD} +### SENS_MPDT3_ROT (`INT32`) {#SENS_MPDT3_ROT} -MXS Serial Communication Baud rate. +MappyDot Sensor 3 Rotation. -Baudrate for the Serial Port connected to the MXS Transponder +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: 38400 -- `1`: 600 -- `2`: 4800 -- `3`: 9600 -- `4`: RESERVED -- `5`: 57600 -- `6`: 115200 -- `7`: 230400 -- `8`: 19200 -- `9`: 460800 -- `10`: 921600 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | 0 | 10 | | 5 | +| ✓ | 0 | 7 | | 0 | -### SER_RC_BAUD (`INT32`) {#SER_RC_BAUD} +### SENS_MPDT4_ROT (`INT32`) {#SENS_MPDT4_ROT} -Baudrate for the Radio Controller Serial Port. +MappyDot Sensor 4 Rotation. -Configure the Baudrate for the Radio Controller Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 0 | +| ✓ | 0 | 7 | | 0 | -### SER_TEL1_BAUD (`INT32`) {#SER_TEL1_BAUD} +### SENS_MPDT5_ROT (`INT32`) {#SENS_MPDT5_ROT} -Baudrate for the TELEM 1 Serial Port. +MappyDot Sensor 5 Rotation. -Configure the Baudrate for the TELEM 1 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 57600 | +| ✓ | 0 | 7 | | 0 | -### SER_TEL2_BAUD (`INT32`) {#SER_TEL2_BAUD} +### SENS_MPDT6_ROT (`INT32`) {#SENS_MPDT6_ROT} -Baudrate for the TELEM 2 Serial Port. +MappyDot Sensor 6 Rotation. -Configure the Baudrate for the TELEM 2 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 921600 | +| ✓ | 0 | 7 | | 0 | -### SER_TEL3_BAUD (`INT32`) {#SER_TEL3_BAUD} +### SENS_MPDT7_ROT (`INT32`) {#SENS_MPDT7_ROT} -Baudrate for the TELEM 3 Serial Port. +MappyDot Sensor 7 Rotation. -Configure the Baudrate for the TELEM 3 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 - +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° + | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 57600 | +| ✓ | 0 | 7 | | 0 | -### SER_TEL4_BAUD (`INT32`) {#SER_TEL4_BAUD} +### SENS_MPDT8_ROT (`INT32`) {#SENS_MPDT8_ROT} -Baudrate for the TELEM/SERIAL 4 Serial Port. +MappyDot Sensor 8 Rotation. -Configure the Baudrate for the TELEM/SERIAL 4 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 57600 | +| ✓ | 0 | 7 | | 0 | -### SER_URT6_BAUD (`INT32`) {#SER_URT6_BAUD} +### SENS_MPDT9_ROT (`INT32`) {#SENS_MPDT9_ROT} -Baudrate for the UART 6 Serial Port. +MappyDot Sensor 9 Rotation. -Configure the Baudrate for the UART 6 Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +This parameter defines the rotation of the Mappydot sensor relative to the platform. **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: No rotation +- `1`: Yaw 45° +- `2`: Yaw 90° +- `3`: Yaw 135° +- `4`: Yaw 180° +- `5`: Yaw 225° +- `6`: Yaw 270° +- `7`: Yaw 315° | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 57600 | - -### SER_WIFI_BAUD (`INT32`) {#SER_WIFI_BAUD} +| ✓ | 0 | 7 | | 0 | -Baudrate for the Wifi Port Serial Port. +### SENS_OR_ADIS164X (`INT32`) {#SENS_OR_ADIS164X} -Configure the Baudrate for the Wifi Port Serial Port. -Note: certain drivers such as the GPS can determine the Baudrate automatically. +Analog Devices ADIS16448 IMU Orientation(external SPI). **Values:** -- `0`: Auto -- `50`: 50 8N1 -- `75`: 75 8N1 -- `110`: 110 8N1 -- `134`: 134 8N1 -- `150`: 150 8N1 -- `200`: 200 8N1 -- `300`: 300 8N1 -- `600`: 600 8N1 -- `1200`: 1200 8N1 -- `1800`: 1800 8N1 -- `2400`: 2400 8N1 -- `4800`: 4800 8N1 -- `9600`: 9600 8N1 -- `19200`: 19200 8N1 -- `38400`: 38400 8N1 -- `57600`: 57600 8N1 -- `115200`: 115200 8N1 -- `230400`: 230400 8N1 -- `460800`: 460800 8N1 -- `500000`: 500000 8N1 -- `921600`: 921600 8N1 -- `1000000`: 1000000 8N1 -- `1500000`: 1500000 8N1 -- `2000000`: 2000000 8N1 -- `3000000`: 3000000 8N1 +- `0`: ROTATION_NONE +- `4`: ROTATION_YAW_180 | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | | | | 1 | +| ✓ | 0 | 101 | | 0 | -## Simulation +### SENS_SF0X_CFG (`INT32`) {#SENS_SF0X_CFG} -### SIM_GZ_EN_ASPD (`INT32`) {#SIM_GZ_EN_ASPD} +Serial Configuration for Lightware Laser Rangefinder (serial). -Enable airspeed sensor in Gazebo bridge. +Configure on which serial port to run Lightware Laser Rangefinder (serial). **Values:** - `0`: Disabled -- `1`: Enabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + +### SENS_TEMP_ID (`INT32`) {#SENS_TEMP_ID} + +Target IMU device ID to regulate temperature. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | + +### SENS_TFLOW_CFG (`INT32`) {#SENS_TFLOW_CFG} -### SIM_GZ_EN_BARO (`INT32`) {#SIM_GZ_EN_BARO} +Serial Configuration for ThoneFlow-3901U optical flow sensor. -Enable barometer/air pressure sensor in Gazebo bridge. +Configure on which serial port to run ThoneFlow-3901U optical flow sensor. **Values:** - `0`: Disabled -- `1`: Enabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + +### SENS_TFMINI_CFG (`INT32`) {#SENS_TFMINI_CFG} -### SIM_GZ_EN_FLOW (`INT32`) {#SIM_GZ_EN_FLOW} +Serial Configuration for Benewake TFmini Rangefinder. -Enable optical flow sensor in Gazebo bridge. +Configure on which serial port to run Benewake TFmini Rangefinder. **Values:** - `0`: Disabled -- `1`: Enabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + +### SENS_TFMINI_HW (`INT32`) {#SENS_TFMINI_HW} -### SIM_GZ_EN_GPS (`INT32`) {#SIM_GZ_EN_GPS} +Hardware Model. -Enable GPS/NavSat sensor in Gazebo bridge. +Models differ in range and FoV. **Values:** -- `0`: Disabled -- `1`: Enabled +- `1`: TFMINI +- `2`: ISTRA24 +- `3`: ISTRA24_100m -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | 3 | | 1 | -### SIM_GZ_EN_LIDAR (`INT32`) {#SIM_GZ_EN_LIDAR} +### SENS_ULAND_CFG (`INT32`) {#SENS_ULAND_CFG} + +Serial Configuration for uLanding Radar. -Enable laser/lidar sensors in Gazebo bridge. +Configure on which serial port to run uLanding Radar. **Values:** - `0`: Disabled -- `1`: Enabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | + +### SENS_VN_CFG (`INT32`) {#SENS_VN_CFG} -### SIM_GZ_EN_ODOM (`INT32`) {#SIM_GZ_EN_ODOM} +Serial Configuration for VectorNav (VN-100, VN-200, VN-300). -Enable odometry in Gazebo bridge. +Configure on which serial port to run VectorNav (VN-100, VN-200, VN-300). **Values:** - `0`: Disabled -- `1`: Enabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ----------- | ---- | -| ✓ | | | | Enabled (1) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -## Simulation In Hardware +### SF45_ORIENT_CFG (`INT32`) {#SF45_ORIENT_CFG} -### SIH_DISTSNSR_MAX (`FLOAT`) {#SIH_DISTSNSR_MAX} +Orientation upright or facing downward. -distance sensor maximum range. +The SF45 mounted facing upward or downward on the frame -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1000.0 | 0.01 | 100.0 | m | +**Values:** -### SIH_DISTSNSR_MIN (`FLOAT`) {#SIH_DISTSNSR_MIN} +- `24`: Rotation upward +- `25`: Rotation downward -distance sensor minimum range. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 24 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 10.0 | 0.01 | 0.0 | m | +### SF45_UPDATE_CFG (`INT32`) {#SF45_UPDATE_CFG} -### SIH_DISTSNSR_OVR (`FLOAT`) {#SIH_DISTSNSR_OVR} +Update rate in Hz. -if >= 0 the distance sensor measures will be overridden by this value. +The SF45 sets the update rate in Hz to allow greater resolution -Absolute value superior to 10000 will disable distance sensor +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | -1.0 | m | +- `1`: 50hz +- `2`: 100hz +- `3`: 200hz +- `4`: 400hz +- `5`: 500hz +- `6`: 625hz +- `7`: 1000hz +- `8`: 1250hz +- `9`: 1538hz +- `10`: 2000hz +- `11`: 2500hz +- `12`: 5000hz -### SIH_IXX (`FLOAT`) {#SIH_IXX} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 5 | -Vehicle inertia about X axis. +### SF45_YAW_CFG (`INT32`) {#SF45_YAW_CFG} -The inertia is a 3 by 3 symmetric matrix. -It represents the difficulty of the vehicle to modify its angular rate. +Sensor facing forward or backward. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------ | -|   | 0.0 | | 0.005 | 0.025 | kg m^2 | +The usb port on the sensor indicates 180deg, opposite usb is forward facing -### SIH_IXY (`FLOAT`) {#SIH_IXY} +**Values:** -Vehicle cross term inertia xy. +- `0`: Rotation forward +- `2`: Rotation right +- `4`: Rotation backward +- `6`: Rotation left -The inertia is a 3 by 3 symmetric matrix. -This value can be set to 0 for a quad symmetric about its center of mass. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------ | -|   | | | 0.005 | 0.0 | kg m^2 | +### SIM_ARSPD_FAIL (`INT32`) {#SIM_ARSPD_FAIL} -### SIH_IXZ (`FLOAT`) {#SIH_IXZ} +Dynamically simulate failure of airspeed sensor instance. -Vehicle cross term inertia xz. +**Values:** -The inertia is a 3 by 3 symmetric matrix. -This value can be set to 0 for a quad symmetric about its center of mass. +- `0`: Disabled +- `1`: Enabled -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------ | -|   | | | 0.005 | 0.0 | kg m^2 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1 | | 0 | -### SIH_IYY (`FLOAT`) {#SIH_IYY} +### VN_MODE (`INT32`) {#VN_MODE} -Vehicle inertia about Y axis. +VectorNav driver mode. -The inertia is a 3 by 3 symmetric matrix. -It represents the difficulty of the vehicle to modify its angular rate. +INS or sensors -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------ | -|   | 0.0 | | 0.005 | 0.025 | kg m^2 | +**Values:** -### SIH_IYZ (`FLOAT`) {#SIH_IYZ} +- `0`: Sensors Only (default) +- `1`: INS -Vehicle cross term inertia yz. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---- | +|   | | | | 0 | -The inertia is a 3 by 3 symmetric matrix. -This value can be set to 0 for a quad symmetric about its center of mass. +### VOXLPM_SHUNT_BAT (`FLOAT`) {#VOXLPM_SHUNT_BAT} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------ | -|   | | | 0.005 | 0.0 | kg m^2 | +VOXL Power Monitor Shunt, Battery. -### SIH_IZZ (`FLOAT`) {#SIH_IZZ} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | ----------- | -------- | ---------- | ------- | ---- | +| ✓ | 0.000000001 | 0.1 | .000000001 | 0.00063 | -Vehicle inertia about Z axis. +### VOXLPM_SHUNT_REG (`FLOAT`) {#VOXLPM_SHUNT_REG} -The inertia is a 3 by 3 symmetric matrix. -It represents the difficulty of the vehicle to modify its angular rate. +VOXL Power Monitor Shunt, Regulator. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------ | -|   | 0.0 | | 0.005 | 0.030 | kg m^2 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | ----------- | -------- | ---------- | ------- | ---- | +| ✓ | 0.000000001 | 0.1 | .000000001 | 0.0056 | -### SIH_KDV (`FLOAT`) {#SIH_KDV} +## Septentrio -First order drag coefficient. +### SEP_AUTO_CONFIG (`INT32`) {#SEP_AUTO_CONFIG} -Physical coefficient representing the friction with air particules. -The greater this value, the slower the quad will move. -Drag force function of velocity: D=-KDV*V. -The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s] +Toggle automatic receiver configuration. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------- | -|   | 0.0 | | 0.05 | 1.0 | N/(m/s) | +By default, the receiver is automatically configured. Sometimes it may be used for multiple purposes. If the offered parameters aren't sufficient, this parameter can be disabled to have full control of the receiver configuration. A good way to use this is to enable automatic configuration, let the receiver be configured, and then disable it to make manual adjustments. -### SIH_KDW (`FLOAT`) {#SIH_KDW} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ----------- | ---- | +| ✓ | | | | Enabled (1) | -First order angular damper coefficient. +### SEP_CONST_USAGE (`INT32`) {#SEP_CONST_USAGE} -Physical coefficient representing the friction with air particules during rotations. -The greater this value, the slower the quad will rotate. -Aerodynamic moment function of body rate: Ma=-KDW\*W_B. -This value can be set to 0 if unknown. +Usage of different constellations. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---------- | -|   | 0.0 | | 0.005 | 0.025 | Nm/(rad/s) | +Choice of which constellations the receiver should use for PVT computation. When this is 0, the constellation usage isn't changed. -### SIH_LOC_H0 (`FLOAT`) {#SIH_LOC_H0} +**Bitmask:** -Initial AMSL ground altitude. +- `0`: GPS +- `1`: GLONASS +- `2`: Galileo +- `3`: SBAS +- `4`: BeiDou + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 63 | | 0 | + +### SEP_DUMP_COMM (`INT32`) {#SEP_DUMP_COMM} + +Log GPS communication data. + +Log raw communication between the driver and connected receivers. For example, "To receiver" will log all commands and corrections sent by the driver to the receiver. -This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. -If using FlightGear as a visual animation, -this value can be tweaked such that the vehicle lies on the ground at takeoff. -LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others -to represent a physical ground location on Earth. +**Values:** + +- `0`: Disabled +- `1`: From receiver +- `2`: To receiver +- `3`: Both | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -420.0 | 8848.0 | 0.01 | 489.4 | m | +|   | 0 | 3 | | 0 | -### SIH_LOC_LAT0 (`FLOAT`) {#SIH_LOC_LAT0} +### SEP_HARDW_SETUP (`INT32`) {#SEP_HARDW_SETUP} -Initial geodetic latitude. +Setup and expected use of the hardware. -This value represents the North-South location on Earth where the simulation begins. -LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others -to represent a physical ground location on Earth. +- Default: Use two receivers as completely separate instances. - Moving base: Use two receivers in a rover & moving base setup for heading. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | --------- | ---- | -|   | -90 | 90 | | 47.397742 | deg | +**Values:** -### SIH_LOC_LON0 (`FLOAT`) {#SIH_LOC_LON0} +- `0`: Default +- `1`: Moving base -Initial geodetic longitude. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 1 | | 0 | -This value represents the East-West location on Earth where the simulation begins. -LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others -to represent a physical ground location on Earth. +### SEP_LOG_FORCE (`INT32`) {#SEP_LOG_FORCE} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | -------- | ---- | -|   | -180 | 180 | | 8.545594 | deg | +Whether to overwrite or add to existing logging. -### SIH_L_PITCH (`FLOAT`) {#SIH_L_PITCH} +When the receiver is already set up to log data, this decides whether extra logged data should be added or overwrite existing data. -Pitch arm length. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -This is the arm length generating the pitching moment -This value can be measured with a ruler. -This corresponds to half the distance between the front and rear motors. +### SEP_LOG_HZ (`INT32`) {#SEP_LOG_HZ} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.05 | 0.2 | m | +Logging frequency for the receiver. -### SIH_L_ROLL (`FLOAT`) {#SIH_L_ROLL} +Select the frequency at which the connected receiver should log data to its internal storage. -Roll arm length. +**Values:** -This is the arm length generating the rolling moment -This value can be measured with a ruler. -This corresponds to half the distance between the left and right motors. +- `0`: Disabled +- `1`: 0.1 Hz +- `2`: 0.2 Hz +- `3`: 0.5 Hz +- `4`: 1 Hz +- `5`: 2 Hz +- `6`: 5 Hz +- `7`: 10 Hz +- `8`: 20 Hz +- `9`: 25 Hz +- `10`: 50 Hz -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.05 | 0.2 | m | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 10 | | 0 | -### SIH_MASS (`FLOAT`) {#SIH_MASS} +### SEP_LOG_LEVEL (`INT32`) {#SEP_LOG_LEVEL} -Vehicle mass. +Logging level for the receiver. -This value can be measured by weighting the quad on a scale. +Select the level of detail that needs to be logged by the receiver. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.1 | 1.0 | kg | +**Values:** -### SIH_Q_MAX (`FLOAT`) {#SIH_Q_MAX} +- `0`: Lite +- `1`: Basic +- `2`: Default +- `3`: Full -Max propeller torque. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 3 | | 2 | -This is the maximum torque delivered by one propeller -when the motor is running at full speed. -This value is usually about few percent of the maximum thrust force. +### SEP_OUTP_HZ (`INT32`) {#SEP_OUTP_HZ} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.05 | 0.1 | Nm | +Output frequency of main SBF blocks. -### SIH_T_MAX (`FLOAT`) {#SIH_T_MAX} +The output frequency of the main SBF blocks needed for PVT information. -Max propeller thrust force. +**Values:** -This is the maximum force delivered by one propeller -when the motor is running at full speed. -This value is usually about 5 times the mass of the quadrotor. +- `0`: 5 Hz +- `1`: 10 Hz +- `2`: 20 Hz +- `3`: 25 Hz -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.5 | 5.0 | N | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 3 | | 1 | -### SIH_T_TAU (`FLOAT`) {#SIH_T_TAU} +### SEP_PITCH_OFFS (`FLOAT`) {#SEP_PITCH_OFFS} -thruster time constant tau. +Pitch offset for dual antenna GPS. -the time taken for the thruster to step from 0 to 100% should be about 4 times tau +Vertical offsets can be compensated for by adjusting the Pitch offset. Note that this can be interpreted as the "roll" angle in case the antennas are aligned along the perpendicular axis. This occurs in situations where the two antenna ARPs may not be exactly at the same height in the vehicle reference frame. Since pitch is defined as the right-handed rotation about the vehicle Y axis, a situation where the main antenna is mounted lower than the aux antenna (assuming the default antenna setup) will result in a positive pitch. + +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | -90 | 90 | | 0 | deg | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.05 | s | +### SEP_PORT1_CFG (`INT32`) {#SEP_PORT1_CFG} -### SIH_VEHICLE_TYPE (`INT32`) {#SIH_VEHICLE_TYPE} +Serial Configuration for GPS Port. -Vehicle type. +Configure on which serial port to run GPS Port. **Values:** -- `0`: Quadcopter -- `1`: Fixed-Wing -- `2`: Tailsitter -- `3`: Standard VTOL -- `4`: Hexacopter -- `5`: Rover Ackermann +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 0 | -## Simulator - -### SIM_AGP_FAIL (`INT32`) {#SIM_AGP_FAIL} - -AGP failure mode. - -Stuck: freeze the measurement to the current location -Drift: add a linearly growing bias to the sensor data +### SEP_PORT2_CFG (`INT32`) {#SEP_PORT2_CFG} -**Bitmask:** +Serial Configuration for Secondary GPS port. -- `0`: Stuck -- `1`: Drift +Configure on which serial port to run Secondary GPS port. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 3 | | 0 | +**Values:** -### SIM_BARO_OFF_P (`FLOAT`) {#SIM_BARO_OFF_P} +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -simulated barometer pressure offset. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.0 | +### SEP_SAT_INFO (`INT32`) {#SEP_SAT_INFO} -### SIM_BARO_OFF_T (`FLOAT`) {#SIM_BARO_OFF_T} +Enable sat info. -simulated barometer temperature offset. +Enable publication of satellite info (ORB_ID(satellite_info)) if possible. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ------- | -|   | | | | 0.0 | celcius | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------------ | ---- | +| ✓ | | | | Disabled (0) | -### SIM_GPS_USED (`INT32`) {#SIM_GPS_USED} +### SEP_STREAM_LOG (`INT32`) {#SEP_STREAM_LOG} -simulated GPS number of satellites used. +Logging stream used during automatic configuration. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 50 | | 10 | +The stream the autopilot sets up on the receiver to output the logging data. Set this to another value if the default stream is already used for another purpose. -### SIM_MAG_OFFSET_X (`FLOAT`) {#SIM_MAG_OFFSET_X} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | 10 | | 2 | -simulated magnetometer X offset. +### SEP_STREAM_MAIN (`INT32`) {#SEP_STREAM_MAIN} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +Main stream used during automatic configuration. -### SIM_MAG_OFFSET_Y (`FLOAT`) {#SIM_MAG_OFFSET_Y} +The stream the autopilot sets up on the receiver to output the main data. Set this to another value if the default stream is already used for another purpose. -simulated magnetometer Y offset. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 1 | 10 | | 1 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +### SEP_YAW_OFFS (`FLOAT`) {#SEP_YAW_OFFS} -### SIM_MAG_OFFSET_Z (`FLOAT`) {#SIM_MAG_OFFSET_Z} +Heading/Yaw offset for dual antenna GPS. -simulated magnetometer Z offset. +Heading offset angle for dual antenna GPS setups that support heading estimation. Set this to 0 if the antennas are parallel to the forward-facing direction of the vehicle and the rover antenna is in front. The offset angle increases clockwise. Set this to 90 if the rover antenna is placed on the right side of the vehicle and the moving base antenna is on the left side. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | | | | 0.0 | gauss | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | -360 | 360 | | 0 | deg | -## Spacecraft Attitude Control +## Serial -### SC_PITCHRATE_MAX (`FLOAT`) {#SC_PITCHRATE_MAX} +### RC_CRSF_PRT_CFG (`INT32`) {#RC_CRSF_PRT_CFG} -Max pitch rate. +Serial Configuration for CRSF RC Input Driver. -Limit for pitch rate in manual and auto modes (except acro). -Has effect for large rotations in autonomous mode, to avoid large control -output and mixer saturation. -This is not only limited by the vehicle's properties, but also by the maximum -measurement rate of the gyro. +Configure on which serial port to run CRSF RC Input Driver. Crossfire RC (CRSF) driver. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.0 | 1800.0 | 5 | 220.0 | deg/s | +**Values:** -### SC_PITCH_P (`FLOAT`) {#SC_PITCH_P} +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -Pitch P gain. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. +### RC_DSM_PRT_CFG (`INT32`) {#RC_DSM_PRT_CFG} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 12 | 0.1 | 6.5 | +Serial Configuration for DSM RC Input Driver. -### SC_ROLLRATE_MAX (`FLOAT`) {#SC_ROLLRATE_MAX} +Configure on which serial port to run DSM RC Input Driver. DSM RC (Spektrum) driver. -Max roll rate. +**Values:** -Limit for roll rate in manual and auto modes (except acro). -Has effect for large rotations in autonomous mode, to avoid large control -output and mixer saturation. -This is not only limited by the vehicle's properties, but also by the maximum -measurement rate of the gyro. +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.0 | 1800.0 | 5 | 220.0 | deg/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -### SC_ROLL_P (`FLOAT`) {#SC_ROLL_P} +### RC_GHST_PRT_CFG (`INT32`) {#RC_GHST_PRT_CFG} -Roll P gain. +Serial Configuration for GHST RC Input Driver. -Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. +Configure on which serial port to run GHST RC Input Driver. Ghost (GHST) RC driver. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 12 | 0.1 | 6.5 | +**Values:** -### SC_YAWRATE_MAX (`FLOAT`) {#SC_YAWRATE_MAX} +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -Max yaw rate. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.0 | 1800.0 | 5 | 200.0 | deg/s | +### RC_PORT_CONFIG (`INT32`) {#RC_PORT_CONFIG} -### SC_YAW_P (`FLOAT`) {#SC_YAW_P} +Serial Configuration for RC Input Driver. -Yaw P gain. +Configure on which serial port to run RC Input Driver. Setting this to 'Disabled' will use a board-specific default port for RC input. -Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 5 | 0.1 | 2.8 | +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -### SC_YAW_WEIGHT (`FLOAT`) {#SC_YAW_WEIGHT} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 300 | -Yaw weight. +### RC_SBUS_PRT_CFG (`INT32`) {#RC_SBUS_PRT_CFG} -A fraction [0,1] deprioritizing yaw compared to roll and pitch in non-linear attitude control. -Deprioritizing yaw is necessary because multicopters have much less control authority -in yaw compared to the other axes and it makes sense because yaw is not critical for -stable hovering or 3D navigation. -For yaw control tuning use SC_YAW_P. This ratio has no impact on the yaw gain. +Serial Configuration for SBUS RC Input Driver. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1.0 | 0.1 | 0.4 | +Configure on which serial port to run SBUS RC Input Driver. SBUS RC driver. -## Spacecraft Position Control +**Values:** -### SC_MAN_TILT_TAU (`FLOAT`) {#SC_MAN_TILT_TAU} +- `0`: Disabled +- `6`: UART 6 +- `101`: TELEM 1 +- `102`: TELEM 2 +- `103`: TELEM 3 +- `104`: TELEM/SERIAL 4 +- `201`: GPS 1 +- `202`: GPS 2 +- `203`: GPS 3 +- `300`: Radio Controller +- `301`: Wifi Port +- `401`: EXT2 -Manual tilt input filter time constant. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 300 | -Setting this parameter to 0 disables the filter +### SER_EXT2_BAUD (`INT32`) {#SER_EXT2_BAUD} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 2.0 | | 0.0 | s | +Baudrate for the EXT2 Serial Port. -### SC_MAN_Y_SCALE (`FLOAT`) {#SC_MAN_Y_SCALE} +Configure the Baudrate for the EXT2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -Max manual yaw rate for Stabilized, Altitude, Position mode. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0 | 400 | 10 | 150. | deg/s | +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -### SPC_ACC (`FLOAT`) {#SPC_ACC} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 57600 | -Acceleration for autonomous and for manual modes. +### SER_GPS1_BAUD (`INT32`) {#SER_GPS1_BAUD} -When piloting manually, this parameter is only used in MPC_POS_MODE 4. +Baudrate for the GPS 1 Serial Port. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 2 | 15 | 1 | 3. | m/s^2 | +Configure the Baudrate for the GPS 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -### SPC_ACC_MAX (`FLOAT`) {#SPC_ACC_MAX} +**Values:** -Maximum accelaration in autonomous modes. +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 2 | 15 | 1 | 5. | m/s^2 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -### SPC_JERK_AUTO (`FLOAT`) {#SPC_JERK_AUTO} +### SER_GPS2_BAUD (`INT32`) {#SER_GPS2_BAUD} -Jerk limit in autonomous modes. +Baudrate for the GPS 2 Serial Port. -Limit the maximum jerk of the vehicle (how fast the acceleration can change). -A lower value leads to smoother vehicle motions but also limited agility. +Configure the Baudrate for the GPS 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 1 | 80 | 1 | 4. | m/s^3 | +**Values:** -### SPC_JERK_MAX (`FLOAT`) {#SPC_JERK_MAX} +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -Maximum jerk in Position/Altitude mode. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -Limit the maximum jerk of the vehicle (how fast the acceleration can change). -A lower value leads to smoother motions but limits agility -(how fast it can change directions or break). -Setting this to the maximum value essentially disables the limit. -Only used with smooth MPC_POS_MODE 3 and 4. +### SER_GPS3_BAUD (`INT32`) {#SER_GPS3_BAUD} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.5 | 500 | 1 | 8. | m/s^3 | +Baudrate for the GPS 3 Serial Port. -### SPC_MAN_Y_MAX (`FLOAT`) {#SPC_MAN_Y_MAX} +Configure the Baudrate for the GPS 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -Max manual yaw rate for Stabilized, Altitude, Position mode. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0 | 400 | 10 | 150. | deg/s | +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -### SPC_MAN_Y_TAU (`FLOAT`) {#SPC_MAN_Y_TAU} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -Manual yaw rate input filter time constant. +### SER_MXS_BAUD (`INT32`) {#SER_MXS_BAUD} -Not used in Stabilized mode -Setting this parameter to 0 disables the filter +MXS Serial Communication Baud rate. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 5 | 0.01 | 0.08 | s | +Baudrate for the Serial Port connected to the MXS Transponder -### SPC_POS_I (`FLOAT`) {#SPC_POS_I} +**Values:** -Integral gain for position error. +- `0`: 38400 +- `1`: 600 +- `2`: 4800 +- `3`: 9600 +- `4`: RESERVED +- `5`: 57600 +- `6`: 115200 +- `7`: 230400 +- `8`: 19200 +- `9`: 460800 +- `10`: 921600 -Defined as corrective velocity in m/s per m velocity error +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | 0 | 10 | | 5 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | 0.1 | 0. | +### SER_RC_BAUD (`INT32`) {#SER_RC_BAUD} -### SPC_POS_I_LIM (`FLOAT`) {#SPC_POS_I_LIM} +Baudrate for the Radio Controller Serial Port. -Integral limit for position error. +Configure the Baudrate for the Radio Controller Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -Defined as corrective velocity in m/s per m velocity error +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 5 | 0.01 | 1. | +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -### SPC_POS_P (`FLOAT`) {#SPC_POS_P} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -Proportional gain for position error. +### SER_TEL1_BAUD (`INT32`) {#SER_TEL1_BAUD} -Defined as corrective velocity in m/s per m position error +Baudrate for the TELEM 1 Serial Port. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 2 | 0.1 | 0.2 | +Configure the Baudrate for the TELEM 1 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -### SPC_THR_MAX (`FLOAT`) {#SPC_THR_MAX} +**Values:** -Maximum collective thrust. +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -Limit allowed thrust +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 57600 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | 0.05 | 1. | norm | +### SER_TEL2_BAUD (`INT32`) {#SER_TEL2_BAUD} -### SPC_VELD_LP (`FLOAT`) {#SPC_VELD_LP} +Baudrate for the TELEM 2 Serial Port. -Numerical velocity derivative low pass cutoff frequency. +Configure the Baudrate for the TELEM 2 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 10 | 0.5 | 5.0 | Hz | +**Values:** -### SPC_VEL_ALL (`FLOAT`) {#SPC_VEL_ALL} +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -Overall Velocity Limit. +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 921600 | -If set to a value greater than zero, other parameters are automatically set (such as -MPC_VEL_MAX or MPC_VEL_MANUAL). -If set to a negative value, the existing individual parameters are used. +### SER_TEL3_BAUD (`INT32`) {#SER_TEL3_BAUD} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | -20 | 20 | 1 | -10. | +Baudrate for the TELEM 3 Serial Port. -### SPC_VEL_CRUISE (`FLOAT`) {#SPC_VEL_CRUISE} +Configure the Baudrate for the TELEM 3 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -Cruising elocity setpoint in autonomous modes. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 3 | 20 | 1 | 10. | m/s | +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -### SPC_VEL_D (`FLOAT`) {#SPC_VEL_D} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 57600 | -Derivative gain for velocity error. +### SER_TEL4_BAUD (`INT32`) {#SER_TEL4_BAUD} -Defined as corrective acceleration in m/s^2 per m/s velocity error +Baudrate for the TELEM/SERIAL 4 Serial Port. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 15 | 0.1 | 0.0 | +Configure the Baudrate for the TELEM/SERIAL 4 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -### SPC_VEL_I (`FLOAT`) {#SPC_VEL_I} +**Values:** -Integral gain for velocity error. +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -Defined as corrective acceleration in m/s^2 per m/s velocity error +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 57600 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | 0.1 | 0. | +### SER_URT6_BAUD (`INT32`) {#SER_URT6_BAUD} -### SPC_VEL_I_LIM (`FLOAT`) {#SPC_VEL_I_LIM} +Baudrate for the UART 6 Serial Port. -Integral limit for velocity error. +Configure the Baudrate for the UART 6 Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -Defined as corrective acceleration in m/s^2 per m/s velocity error +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 5 | 0.1 | 1. | +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -### SPC_VEL_MANUAL (`FLOAT`) {#SPC_VEL_MANUAL} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 57600 | -Maximum velocity setpoint in Position mode. +### SER_WIFI_BAUD (`INT32`) {#SER_WIFI_BAUD} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 3 | 20 | 1 | 10. | m/s | +Baudrate for the Wifi Port Serial Port. -### SPC_VEL_MAX (`FLOAT`) {#SPC_VEL_MAX} +Configure the Baudrate for the Wifi Port Serial Port. Note: certain drivers such as the GPS can determine the Baudrate automatically. -Maximum velocity. +**Values:** -Absolute maximum for all velocity controlled modes. -Any higher value is truncated. +- `0`: Auto +- `50`: 50 8N1 +- `75`: 75 8N1 +- `110`: 110 8N1 +- `134`: 134 8N1 +- `150`: 150 8N1 +- `200`: 200 8N1 +- `300`: 300 8N1 +- `600`: 600 8N1 +- `1200`: 1200 8N1 +- `1800`: 1800 8N1 +- `2400`: 2400 8N1 +- `4800`: 4800 8N1 +- `9600`: 9600 8N1 +- `19200`: 19200 8N1 +- `38400`: 38400 8N1 +- `57600`: 57600 8N1 +- `115200`: 115200 8N1 +- `230400`: 230400 8N1 +- `460800`: 460800 8N1 +- `500000`: 500000 8N1 +- `921600`: 921600 8N1 +- `1000000`: 1000000 8N1 +- `1500000`: 1500000 8N1 +- `2000000`: 2000000 8N1 +- `3000000`: 3000000 8N1 -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 20 | 1 | 12. | m/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 1 | -### SPC_VEL_P (`FLOAT`) {#SPC_VEL_P} +## Simulation In Hardware -Proportional gain for velocity error. +### SIH_DISTSNSR_MAX (`FLOAT`) {#SIH_DISTSNSR_MAX} -Defined as corrective acceleration in m/s^2 per m/s velocity error +distance sensor maximum range. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 15 | 0.1 | 6.55 | - -## Spacecraft Rate Control - -### SC_ACRO_EXPO (`FLOAT`) {#SC_ACRO_EXPO} +|   | 0.0 | 1000.0 | 0.01 | 100.0 | m | -Acro mode Expo factor for Roll and Pitch. +### SIH_DISTSNSR_MIN (`FLOAT`) {#SIH_DISTSNSR_MIN} -Exponential factor for tuning the input curve shape. -0 Purely linear input curve -1 Purely cubic input curve +distance sensor minimum range. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 0.69 | +|   | 0.0 | 10.0 | 0.01 | 0.0 | m | -### SC_ACRO_EXPO_Y (`FLOAT`) {#SC_ACRO_EXPO_Y} +### SIH_DISTSNSR_OVR (`FLOAT`) {#SIH_DISTSNSR_OVR} -Acro mode Expo factor for Yaw. +if >= 0 the distance sensor measures will be overridden by this value. -Exponential factor for tuning the input curve shape. -0 Purely linear input curve -1 Purely cubic input curve +Absolute value superior to 10000 will disable distance sensor | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 0.69 | +|   | | | | -1.0 | m | -### SC_ACRO_P_MAX (`FLOAT`) {#SC_ACRO_P_MAX} +### SIH_IXX (`FLOAT`) {#SIH_IXX} -Max acro pitch rate. +Vehicle inertia about X axis. -default: 2 turns per second +The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.0 | 1800.0 | 5 | 720.0 | deg/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------ | +|   | 0.0 | | 0.005 | 0.025 | kg m^2 | -### SC_ACRO_R_MAX (`FLOAT`) {#SC_ACRO_R_MAX} +### SIH_IXY (`FLOAT`) {#SIH_IXY} -Max acro roll rate. +Vehicle cross term inertia xy. -default: 2 turns per second +The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.0 | 1800.0 | 5 | 720.0 | deg/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------ | +|   | | | 0.005 | 0.0 | kg m^2 | -### SC_ACRO_SUPEXPO (`FLOAT`) {#SC_ACRO_SUPEXPO} +### SIH_IXZ (`FLOAT`) {#SIH_IXZ} -Acro mode SuperExpo factor for Roll and Pitch. +Vehicle cross term inertia xz. -SuperExpo factor for refining the input curve shape tuned using SC_ACRO_EXPO. -0 Pure Expo function -0.7 reasonable shape enhancement for intuitive stick feel -0.95 very strong bent input curve only near maxima have effect +The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 0.95 | | 0.7 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------ | +|   | | | 0.005 | 0.0 | kg m^2 | -### SC_ACRO_SUPEXPOY (`FLOAT`) {#SC_ACRO_SUPEXPOY} +### SIH_IYY (`FLOAT`) {#SIH_IYY} -Acro mode SuperExpo factor for Yaw. +Vehicle inertia about Y axis. -SuperExpo factor for refining the input curve shape tuned using SC_ACRO_EXPO_Y. -0 Pure Expo function -0.7 reasonable shape enhancement for intuitive stick feel -0.95 very strong bent input curve only near maxima have effect +The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 0.95 | | 0.7 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------ | +|   | 0.0 | | 0.005 | 0.025 | kg m^2 | -### SC_ACRO_Y_MAX (`FLOAT`) {#SC_ACRO_Y_MAX} +### SIH_IYZ (`FLOAT`) {#SIH_IYZ} -Max acro yaw rate. +Vehicle cross term inertia yz. -default 1.5 turns per second +The inertia is a 3 by 3 symmetric matrix. This value can be set to 0 for a quad symmetric about its center of mass. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ----- | -|   | 0.0 | 1800.0 | 5 | 540.0 | deg/s | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------ | +|   | | | 0.005 | 0.0 | kg m^2 | -### SC_BAT_SCALE_EN (`INT32`) {#SC_BAT_SCALE_EN} +### SIH_IZZ (`FLOAT`) {#SIH_IZZ} -Battery power level scaler. +Vehicle inertia about Z axis. -This compensates for voltage drop of the battery over time by attempting to -normalize performance across the operating range of the battery. The copter -should constantly behave as if it was fully charged with reduced max acceleration -at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, -it will still be 0.5 at 60% battery. +The inertia is a 3 by 3 symmetric matrix. It represents the difficulty of the vehicle to modify its angular rate. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------------ | ---- | -|   | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------ | +|   | 0.0 | | 0.005 | 0.030 | kg m^2 | -### SC_MAN_F_MAX (`FLOAT`) {#SC_MAN_F_MAX} +### SIH_KDV (`FLOAT`) {#SIH_KDV} -Manual mode maximum force. +First order drag coefficient. -- +Physical coefficient representing the friction with air particules. The greater this value, the slower the quad will move. Drag force function of velocity: D=-KDV*V. The maximum freefall velocity can be computed as V=10*MASS/KDV [m/s] -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1.0 | | 1.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------- | +|   | 0.0 | | 0.05 | 1.0 | N/(m/s) | -### SC_MAN_T_MAX (`FLOAT`) {#SC_MAN_T_MAX} +### SIH_KDW (`FLOAT`) {#SIH_KDW} -Manual mode maximum torque. +First order angular damper coefficient. -- +Physical coefficient representing the friction with air particules during rotations. The greater this value, the slower the quad will rotate. Aerodynamic moment function of body rate: Ma=-KDW\*W_B. This value can be set to 0 if unknown. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1.0 | | 1.0 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ---------- | +|   | 0.0 | | 0.005 | 0.025 | Nm/(rad/s) | -### SC_PITCHRATE_D (`FLOAT`) {#SC_PITCHRATE_D} +### SIH_LOC_H0 (`FLOAT`) {#SIH_LOC_H0} -Pitch rate D gain. +Initial AMSL ground altitude. -Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. +This value represents the Above Mean Sea Level (AMSL) altitude where the simulation begins. If using FlightGear as a visual animation, this value can be tweaked such that the vehicle lies on the ground at takeoff. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.0005 | 0.003 | - -### SC_PITCHRATE_FF (`FLOAT`) {#SC_PITCHRATE_FF} +|   | -420.0 | 8848.0 | 0.01 | 489.4 | m | -Pitch rate feedforward. +### SIH_LOC_LAT0 (`FLOAT`) {#SIH_LOC_LAT0} -Improves tracking performance. +Initial geodetic latitude. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.0 | +This value represents the North-South location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. -### SC_PITCHRATE_I (`FLOAT`) {#SC_PITCHRATE_I} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | --------- | ---- | +|   | -90 | 90 | | 47.397742 | deg | -Pitch rate I gain. +### SIH_LOC_LON0 (`FLOAT`) {#SIH_LOC_LON0} -Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. +Initial geodetic longitude. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.2 | +This value represents the East-West location on Earth where the simulation begins. LAT0, LON0, H0, MU_X, MU_Y, and MU_Z should ideally be consistent among each others to represent a physical ground location on Earth. -### SC_PITCHRATE_K (`FLOAT`) {#SC_PITCHRATE_K} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | -------- | ---- | +|   | -180 | 180 | | 8.545594 | deg | -Pitch rate controller gain. +### SIH_L_PITCH (`FLOAT`) {#SIH_L_PITCH} -Global gain of the controller. -This gain scales the P, I and D terms of the controller: -output = SC_PITCHRATE_K _ (SC_PITCHRATE_P _ error +Pitch arm length. -- SC_PITCHRATE_I \* error_integral -- SC_PITCHRATE_D \* error_derivative) - Set SC_PITCHRATE_P=1 to implement a PID in the ideal form. - Set SC_PITCHRATE_K=1 to implement a PID in the parallel form. +This is the arm length generating the pitching moment This value can be measured with a ruler. This corresponds to half the distance between the front and rear motors. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 5.0 | 0.0005 | 1.0 | +|   | 0.0 | | 0.05 | 0.2 | m | -### SC_PITCHRATE_P (`FLOAT`) {#SC_PITCHRATE_P} +### SIH_L_ROLL (`FLOAT`) {#SIH_L_ROLL} -Pitch rate P gain. +Roll arm length. -Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. +This is the arm length generating the rolling moment This value can be measured with a ruler. This corresponds to half the distance between the left and right motors. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 0.6 | 0.01 | 0.15 | +|   | 0.0 | | 0.05 | 0.2 | m | -### SC_PR_INT_LIM (`FLOAT`) {#SC_PR_INT_LIM} +### SIH_MASS (`FLOAT`) {#SIH_MASS} -Pitch rate integrator limit. +Vehicle mass. -Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes. +This value can be measured by weighting the quad on a scale. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.30 | +|   | 0.0 | | 0.1 | 1.0 | kg | -### SC_ROLLRATE_D (`FLOAT`) {#SC_ROLLRATE_D} +### SIH_Q_MAX (`FLOAT`) {#SIH_Q_MAX} -Roll rate D gain. +Max propeller torque. -Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. +This is the maximum torque delivered by one propeller when the motor is running at full speed. This value is usually about few percent of the maximum thrust force. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 0.01 | 0.0005 | 0.003 | +|   | 0.0 | | 0.05 | 0.1 | Nm | -### SC_ROLLRATE_FF (`FLOAT`) {#SC_ROLLRATE_FF} +### SIH_T_MAX (`FLOAT`) {#SIH_T_MAX} -Roll rate feedforward. +Max propeller thrust force. -Improves tracking performance. +This is the maximum force delivered by one propeller when the motor is running at full speed. This value is usually about 5 times the mass of the quadrotor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.0 | +|   | 0.0 | | 0.5 | 5.0 | N | -### SC_ROLLRATE_I (`FLOAT`) {#SC_ROLLRATE_I} +### SIH_T_TAU (`FLOAT`) {#SIH_T_TAU} -Roll rate I gain. +thruster time constant tau. -Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. +the time taken for the thruster to step from 0 to 100% should be about 4 times tau | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.2 | - -### SC_ROLLRATE_K (`FLOAT`) {#SC_ROLLRATE_K} +|   | | | | 0.05 | s | -Roll rate controller gain. +### SIH_VEHICLE_TYPE (`INT32`) {#SIH_VEHICLE_TYPE} -Global gain of the controller. -This gain scales the P, I and D terms of the controller: -output = SC_ROLLRATE_K _ (SC_ROLLRATE_P _ error +Vehicle type. -- SC_ROLLRATE_I \* error_integral -- SC_ROLLRATE_D \* error_derivative) - Set SC_ROLLRATE_P=1 to implement a PID in the ideal form. - Set SC_ROLLRATE_K=1 to implement a PID in the parallel form. +**Values:** -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 5.0 | 0.0005 | 1.0 | +- `0`: Quadcopter +- `1`: Fixed-Wing +- `2`: Tailsitter +- `3`: Standard VTOL +- `4`: Hexacopter -### SC_ROLLRATE_P (`FLOAT`) {#SC_ROLLRATE_P} +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | -Roll rate P gain. +## Simulator -Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. +### SIM_AGP_FAIL (`INT32`) {#SIM_AGP_FAIL} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.01 | 0.5 | 0.01 | 0.15 | +AGP failure mode. -### SC_RR_INT_LIM (`FLOAT`) {#SC_RR_INT_LIM} +Stuck: freeze the measurement to the current location Drift: add a linearly growing bias to the sensor data -Roll rate integrator limit. +**Bitmask:** -Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes. +- `0`: Stuck +- `1`: Drift | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.30 | - -### SC_YAWRATE_D (`FLOAT`) {#SC_YAWRATE_D} +|   | 0 | 3 | | 0 | -Yaw rate D gain. +### SIM_BARO_OFF_P (`FLOAT`) {#SIM_BARO_OFF_P} -Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. +simulated barometer pressure offset. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.0 | - -### SC_YAWRATE_FF (`FLOAT`) {#SC_YAWRATE_FF} - -Yaw rate feedforward. +|   | | | | 0.0 | -Improves tracking performance. +### SIM_BARO_OFF_T (`FLOAT`) {#SIM_BARO_OFF_T} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.0 | +simulated barometer temperature offset. -### SC_YAWRATE_I (`FLOAT`) {#SC_YAWRATE_I} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ------- | +|   | | | | 0.0 | celcius | -Yaw rate I gain. +### SIM_GPS_USED (`INT32`) {#SIM_GPS_USED} -Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. +simulated GPS number of satellites used. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.865 | - -### SC_YAWRATE_K (`FLOAT`) {#SC_YAWRATE_K} - -Yaw rate controller gain. - -Global gain of the controller. -This gain scales the P, I and D terms of the controller: -output = SC_YAWRATE_K _ (SC_YAWRATE_P _ error - -- SC_YAWRATE_I \* error_integral -- SC_YAWRATE_D \* error_derivative) - Set SC_YAWRATE_P=1 to implement a PID in the ideal form. - Set SC_YAWRATE_K=1 to implement a PID in the parallel form. +|   | 0 | 50 | | 10 | -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 5.0 | 0.0005 | 1.0 | +### SIM_MAG_OFFSET_X (`FLOAT`) {#SIM_MAG_OFFSET_X} -### SC_YAWRATE_P (`FLOAT`) {#SC_YAWRATE_P} +simulated magnetometer X offset. -Yaw rate P gain. +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. +### SIM_MAG_OFFSET_Y (`FLOAT`) {#SIM_MAG_OFFSET_Y} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 10.0 | 0.01 | 10.0 | +simulated magnetometer Y offset. -### SC_YR_INT_LIM (`FLOAT`) {#SC_YR_INT_LIM} +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | -Yaw rate integrator limit. +### SIM_MAG_OFFSET_Z (`FLOAT`) {#SIM_MAG_OFFSET_Z} -Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes. +simulated magnetometer Z offset. -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | 0.01 | 0.2 | +| Reboot | minValue | maxValue | increment | default | unit | +| ------ | -------- | -------- | --------- | ------- | ----- | +|   | | | | 0.0 | gauss | ## System @@ -37019,9 +33196,7 @@ Number of voltage pulses per one rotor revolution on the capturing pin. Automatically configure default values. -Set to 1 to reset parameters on next system startup (setting defaults). -Platform-specific values are used if available. -RC\* parameters are preserved. +Set to 1 to reset parameters on next system startup (setting defaults). Platform-specific values are used if available. RC\* parameters are preserved. **Values:** @@ -37046,16 +33221,7 @@ CHANGING THIS VALUE REQUIRES A RESTART. Defines the auto-start script used to bo Bootloader update. -If enabled, update the bootloader on the next boot. -WARNING: do not cut the power during an update process, otherwise you will -have to recover using some alternative method (e.g. JTAG). -Instructions: - -- Insert an SD card -- Enable this parameter -- Reboot the board (plug the power or send a reboot command) -- Wait until the board comes back up (or at least 2 minutes) -- If it does not come back, check the file bootlog.txt on the SD card +If enabled, update the bootloader on the next boot. WARNING: do not cut the power during an update process, otherwise you will have to recover using some alternative method (e.g. JTAG). Instructions: - Insert an SD card - Enable this parameter - Reboot the board (plug the power or send a reboot command) - Wait until the board comes back up (or at least 2 minutes) - If it does not come back, check the file bootlog.txt on the SD card | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -37065,10 +33231,7 @@ Instructions: Enable auto start of accelerometer thermal calibration at the next power up. -0 : Set to 0 to do nothing -1 : Set to 1 to start a calibration at next boot -This parameter is reset to zero when the temperature calibration starts. -default (0, no calibration) +0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -37078,10 +33241,7 @@ default (0, no calibration) Enable auto start of barometer thermal calibration at the next power up. -0 : Set to 0 to do nothing -1 : Set to 1 to start a calibration at next boot -This parameter is reset to zero when the temperature calibration starts. -default (0, no calibration) +0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -37091,10 +33251,7 @@ default (0, no calibration) Enable auto start of rate gyro thermal calibration at the next power up. -0 : Set to 0 to do nothing -1 : Set to 1 to start a calibration at next boot -This parameter is reset to zero when the temperature calibration starts. -default (0, no calibration) +0 : Set to 0 to do nothing 1 : Set to 1 to start a calibration at next boot This parameter is reset to zero when the temperature calibration starts. default (0, no calibration) | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -37104,9 +33261,7 @@ default (0, no calibration) Required temperature rise during thermal calibration. -A temperature increase greater than this value is required during calibration. -Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. -If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. +A temperature increase greater than this value is required during calibration. Calibration will complete for each sensor when the temperature increase above the starting temperature exceeds the value set by SYS_CAL_TDEL. If the temperature rise is insufficient, the calibration will continue indefinitely and the board will need to be repowered to exit. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------- | @@ -37136,9 +33291,7 @@ Temperature calibration for each sensor will ignore data if the temperature is l Dataman storage backend. -If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set), -the 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses -non-persistent storage in RAM. +If the board supports persistent storage (i.e., the KConfig variable DATAMAN_PERSISTENT_STORAGE is set), the 'Default storage' backend uses a file on persistent storage. If not supported, this backend uses non-persistent storage in RAM. **Values:** @@ -37154,9 +33307,7 @@ non-persistent storage in RAM. Enable factory calibration mode. -If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. -Note: this is only supported on boards with a separate calibration storage -/fs/mtd_caldata. +If enabled, future sensor calibrations will be stored to /fs/mtd_caldata. Note: this is only supported on boards with a separate calibration storage /fs/mtd_caldata. **Values:** @@ -37172,8 +33323,7 @@ Note: this is only supported on boards with a separate calibration storage Enable failure injection. -If enabled allows MAVLink INJECT_FAILURE commands. -WARNING: the failures can easily cause crashes and are to be used with caution! +If enabled allows MAVLink INJECT_FAILURE commands. WARNING: the failures can easily cause crashes and are to be used with caution! | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -37183,10 +33333,7 @@ WARNING: the failures can easily cause crashes and are to be used with caution! Control if the vehicle has a barometer. -Disable this if the board has no barometer, such as some of the Omnibus -F4 SD variants. -If disabled, the preflight checks will not check for the presence of a -barometer. +Disable this if the board has no barometer, such as some of the Omnibus F4 SD variants. If disabled, the preflight checks will not check for the presence of a barometer. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -37196,9 +33343,7 @@ barometer. Control if the vehicle has a GPS. -Disable this if the system has no GPS. -If disabled, the sensors hub will not process sensor_gps, -and GPS will not be available for the rest of the system. +Disable this if the system has no GPS. If disabled, the sensors hub will not process sensor_gps, and GPS will not be available for the rest of the system. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -37208,8 +33353,7 @@ and GPS will not be available for the rest of the system. Control if and how many magnetometers are expected. -0: System has no magnetometer, preflight checks should pass without one. -1-N: Require the presence of N magnetometer sensors for check to pass. +0: System has no magnetometer, preflight checks should pass without one. 1-N: Require the presence of N magnetometer sensors for check to pass. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -37219,9 +33363,7 @@ Control if and how many magnetometers are expected. Control if the vehicle has an airspeed sensor. -Set this to 0 if the board has no airspeed sensor. -If set to 0, the preflight checks will not check for the presence of an -airspeed sensor. +Set this to 0 if the board has no airspeed sensor. If set to 0, the preflight checks will not check for the presence of an airspeed sensor. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -37231,8 +33373,7 @@ airspeed sensor. Number of distance sensors to check being available. -The preflight check will fail if fewer than this number of distance sensors with valid data is present. -Disable the check with 0. +The preflight check will fail if fewer than this number of distance sensors with valid data is present. Disable the check with 0. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -37248,28 +33389,11 @@ The preflight check will fail if fewer than this number of optical flow sensors | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 1 | | 0 | -### SYS_HF_MAV (`INT32`) {#SYS_HF_MAV} - -Enable FMU SD card hardfault streaming. - -When this is enabled all the hardfaults on the SD card are streamed -over MAVLink. This is useful for cases where the FMU does reset in-flight due -to a hardfault and the SD card may not survive a crash. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ----------- | ---- | -|   | | | | Enabled (1) | - ### SYS_HITL (`INT32`) {#SYS_HITL} Enable HITL/SIH mode on next boot. -While enabled the system will boot in Hardware-In-The-Loop (HITL) -or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. -When disabled the same vehicle can be flown normally. -Set to 'external HITL', if the system should perform as if it were a real -vehicle (the only difference to a real system is then only the parameter -value, which can be used for log analysis). +While enabled the system will boot in Hardware-In-The-Loop (HITL) or Simulation-In-Hardware (SIH) mode and not enable all sensors and checks. When disabled the same vehicle can be flown normally. Set to 'external HITL', if the system should perform as if it were a real vehicle (the only difference to a real system is then only the parameter value, which can be used for log analysis). **Values:** @@ -37286,10 +33410,7 @@ value, which can be used for log analysis). Parameter version. -This is used internally only: an airframe configuration might set an expected -parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup -against SYS_PARAM_VER, and if they do not match, parameters are reset and -reloaded from the airframe configuration. +This is used internally only: an airframe configuration might set an expected parameter version value via PARAM_DEFAULTS_VER. This is checked on bootup against SYS_PARAM_VER, and if they do not match, parameters are reset and reloaded from the airframe configuration. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -39491,14 +35612,6 @@ UAVCAN CAN bus bitrate. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 20000 | 1000000 | | 1000000 | -### CANNODE_NODE_ID (`INT32`) {#CANNODE_NODE_ID} - -UAVCAN CAN node ID (0 for dynamic allocation). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 127 | | 0 | - ### CANNODE_PUB_IMU (`INT32`) {#CANNODE_PUB_IMU} Enable RawIMU pub. @@ -39559,10 +35672,7 @@ UAVCAN CAN bus bitrate. UAVCAN fuel tank fuel type. -This parameter defines the type of fuel used in the vehicle's fuel tank. -0: Unknown -1: Liquid (e.g., gasoline, diesel) -2: Gas (e.g., hydrogen, methane, propane) +This parameter defines the type of fuel used in the vehicle's fuel tank. 0: Unknown 1: Liquid (e.g., gasoline, diesel) 2: Gas (e.g., hydrogen, methane, propane) **Values:** @@ -39588,10 +35698,7 @@ This parameter defines the maximum fuel capacity of the vehicle's fuel tank. UAVCAN mode. -0 - UAVCAN disabled. -1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. -2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. -3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN. +0 - UAVCAN disabled. 1 - Enables support for UAVCAN sensors without dynamic node ID allocation and firmware update. 2 - Enables support for UAVCAN sensors with dynamic node ID allocation and firmware update. 3 - Enables support for UAVCAN sensors and actuators with dynamic node ID allocation and firmware update. Also sets the motor control outputs to UAVCAN. **Values:** @@ -39608,10 +35715,7 @@ UAVCAN mode. Which CAN interfaces to output ESC messages on. -Since ESC messages are high priority and sent at a high rate, it is -recommended to only enable the interfaces that are actually used. -Otherwise, the ESC messages will arbitrate lower priority messages and -starve other nodes on the bus. +Since ESC messages are high priority and sent at a high rate, it is recommended to only enable the interfaces that are actually used. Otherwise, the ESC messages will arbitrate lower priority messages and starve other nodes on the bus. **Bitmask:** @@ -39632,12 +35736,7 @@ starve other nodes on the bus. UAVCAN ANTI_COLLISION light operating mode. -This parameter defines the minimum condition under which the system will command -the ANTI_COLLISION lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +This parameter defines the minimum condition under which the system will command the ANTI_COLLISION lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on **Values:** @@ -39654,12 +35753,7 @@ the ANTI_COLLISION lights on UAVCAN LIGHT_ID_LANDING light operating mode. -This parameter defines the minimum condition under which the system will command -the LIGHT_ID_LANDING lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +This parameter defines the minimum condition under which the system will command the LIGHT_ID_LANDING lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on **Values:** @@ -39676,12 +35770,7 @@ the LIGHT_ID_LANDING lights on UAVCAN RIGHT_OF_WAY light operating mode. -This parameter defines the minimum condition under which the system will command -the RIGHT_OF_WAY lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +This parameter defines the minimum condition under which the system will command the RIGHT_OF_WAY lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on **Values:** @@ -39698,12 +35787,7 @@ the RIGHT_OF_WAY lights on UAVCAN STROBE light operating mode. -This parameter defines the minimum condition under which the system will command -the STROBE lights on -0 - Always off -1 - When autopilot is armed -2 - When autopilot is prearmed -3 - Always on +This parameter defines the minimum condition under which the system will command the STROBE lights on 0 - Always off 1 - When autopilot is armed 2 - When autopilot is prearmed 3 - Always on **Values:** @@ -39720,7 +35804,7 @@ the STROBE lights on UAVCAN Node ID. -Read the specs at https://dronecan.github.io/ to learn more about Node ID. +Read the specs at http://uavcan.org to learn more about Node ID. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -39730,8 +35814,7 @@ Read the specs at https://dronecan.github.io/ to learn more about Node ID. publish Arming Status stream. -Enable UAVCAN Arming Status stream publication -uavcan::equipment::safety::ArmingStatus +Enable UAVCAN Arming Status stream publication uavcan::equipment::safety::ArmingStatus | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39741,8 +35824,7 @@ uavcan::equipment::safety::ArmingStatus publish moving baseline data RTCM stream. -Enable UAVCAN RTCM stream publication -ardupilot::gnss::MovingBaselineData +Enable UAVCAN RTCM stream publication ardupilot::gnss::MovingBaselineData | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39752,8 +35834,7 @@ ardupilot::gnss::MovingBaselineData publish RTCM stream. -Enable UAVCAN RTCM stream publication -uavcan::equipment::gnss::RTCMStream +Enable UAVCAN RTCM stream publication uavcan::equipment::gnss::RTCMStream | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39783,10 +35864,7 @@ This parameter defines the minimum valid range for a rangefinder connected via U subscription airspeed. -Enable UAVCAN airspeed subscriptions. -uavcan::equipment::air_data::IndicatedAirspeed -uavcan::equipment::air_data::TrueAirspeed -uavcan::equipment::air_data::StaticTemperature +Enable UAVCAN airspeed subscriptions. uavcan::equipment::air_data::IndicatedAirspeed uavcan::equipment::air_data::TrueAirspeed uavcan::equipment::air_data::StaticTemperature | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39796,9 +35874,7 @@ uavcan::equipment::air_data::StaticTemperature subscription barometer. -Enable UAVCAN barometer subscription. -uavcan::equipment::air_data::StaticPressure -uavcan::equipment::air_data::StaticTemperature +Enable UAVCAN barometer subscription. uavcan::equipment::air_data::StaticPressure uavcan::equipment::air_data::StaticTemperature | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39808,13 +35884,7 @@ uavcan::equipment::air_data::StaticTemperature subscription battery. -Enable UAVCAN battery subscription. -uavcan::equipment::power::BatteryInfo -ardupilot::equipment::power::BatteryInfoAux -cuav::equipment::power::CBAT -0 - Disable -1 - Use raw data. Recommended for Smart battery -2 - Filter the data with internal battery library (unsupported with CBAT) +Enable UAVCAN battery subscription. uavcan::equipment::power::BatteryInfo ardupilot::equipment::power::BatteryInfoAux 0 - Disable 1 - Use raw data. Recommended for Smart battery 2 - Filter the data with internal battery library **Values:** @@ -39830,8 +35900,7 @@ cuav::equipment::power::CBAT subscription button. -Enable UAVCAN button subscription. -ardupilot::indication::Button +Enable UAVCAN button subscription. ardupilot::indication::Button | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39841,8 +35910,7 @@ ardupilot::indication::Button subscription differential pressure. -Enable UAVCAN differential pressure subscription. -uavcan::equipment::air_data::RawAirData +Enable UAVCAN differential pressure subscription. uavcan::equipment::air_data::RawAirData | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39872,10 +35940,7 @@ Enable UAVCAN fuel tank status subscription. subscription GPS. -Enable UAVCAN GPS subscriptions. -uavcan::equipment::gnss::Fix -uavcan::equipment::gnss::Fix2 -uavcan::equipment::gnss::Auxiliary +Enable UAVCAN GPS subscriptions. uavcan::equipment::gnss::Fix uavcan::equipment::gnss::Fix2 uavcan::equipment::gnss::Auxiliary | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -39885,8 +35950,7 @@ uavcan::equipment::gnss::Auxiliary subscription GPS Relative. -Enable UAVCAN GPS Relative subscription. -ardupilot::gnss::RelPosHeading +Enable UAVCAN GPS Relative subscription. ardupilot::gnss::RelPosHeading | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | @@ -39896,8 +35960,7 @@ ardupilot::gnss::RelPosHeading subscription hygrometer. -Enable UAVCAN hygrometer subscriptions. -dronecan::sensors::hygrometer::Hygrometer +Enable UAVCAN hygrometer subscriptions. dronecan::sensors::hygrometer::Hygrometer | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39907,8 +35970,7 @@ dronecan::sensors::hygrometer::Hygrometer subscription ICE. -Enable UAVCAN internal combustion engine (ICE) subscription. -uavcan::equipment::ice::reciprocating::Status +Enable UAVCAN internal combustion engine (ICE) subscription. uavcan::equipment::ice::reciprocating::Status | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39918,8 +35980,7 @@ uavcan::equipment::ice::reciprocating::Status subscription IMU. -Enable UAVCAN IMU subscription. -uavcan::equipment::ahrs::RawIMU +Enable UAVCAN IMU subscription. uavcan::equipment::ahrs::RawIMU | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39929,31 +35990,17 @@ uavcan::equipment::ahrs::RawIMU subscription magnetometer. -Enable UAVCAN mag subscription. -uavcan::equipment::ahrs::MagneticFieldStrength -uavcan::equipment::ahrs::MagneticFieldStrength2 +Enable UAVCAN mag subscription. uavcan::equipment::ahrs::MagneticFieldStrength uavcan::equipment::ahrs::MagneticFieldStrength2 | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ----------- | ---- | | ✓ | | | | Enabled (1) | -### UAVCAN_SUB_MBD (`INT32`) {#UAVCAN_SUB_MBD} - -subscription MovingBaselineData. - -Enable UAVCAN MovingBaselineData subscription. -ardupilot::gnss::MovingBaselineData - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | - ### UAVCAN_SUB_RNG (`INT32`) {#UAVCAN_SUB_RNG} subscription range finder. -Enable UAVCAN range finder subscription. -uavcan::equipment::range_sensor::Measurement +Enable UAVCAN range finder subscription. uavcan::equipment::range_sensor::Measurement | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------------ | ---- | @@ -39961,85 +36008,66 @@ uavcan::equipment::range_sensor::Measurement ## UUV Attitude Control -### UUV_MGM_PITCH (`FLOAT`) {#UUV_MGM_PITCH} - -Pitch gain for manual inputs in manual control mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.05 | - -### UUV_MGM_ROLL (`FLOAT`) {#UUV_MGM_ROLL} - -Roll gain for manual inputs in manual control mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.05 | - -### UUV_MGM_THRTL (`FLOAT`) {#UUV_MGM_THRTL} +### UUV_DIRCT_PITCH (`FLOAT`) {#UUV_DIRCT_PITCH} -Throttle gain for manual inputs in manual control mode. +Direct pitch input. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.1 | +|   | | | | 0.0 | -### UUV_MGM_YAW (`FLOAT`) {#UUV_MGM_YAW} +### UUV_DIRCT_ROLL (`FLOAT`) {#UUV_DIRCT_ROLL} -Yaw gain for manual inputs in manual control mode. +Direct roll input. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.05 | +|   | | | | 0.0 | -### UUV_PITCH_D (`FLOAT`) {#UUV_PITCH_D} +### UUV_DIRCT_THRUST (`FLOAT`) {#UUV_DIRCT_THRUST} -Pitch differential gain. +Direct thrust input. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 2.0 | +|   | | | | 0.0 | -### UUV_PITCH_P (`FLOAT`) {#UUV_PITCH_P} +### UUV_DIRCT_YAW (`FLOAT`) {#UUV_DIRCT_YAW} -Pitch proportional gain. +Direct yaw input. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 4.0 | - -### UUV_RGM_PITCH (`FLOAT`) {#UUV_RGM_PITCH} +|   | | | | 0.0 | -Pitch gain for manual inputs in rate control mode. +### UUV_INPUT_MODE (`INT32`) {#UUV_INPUT_MODE} -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 100.0 | +Select Input Mode. -### UUV_RGM_ROLL (`FLOAT`) {#UUV_RGM_ROLL} +**Values:** -Roll gain for manual inputs in rate control mode. +- `0`: use Attitude Setpoints +- `1`: Direct Feedthrough | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 100.0 | +|   | | | | 0 | -### UUV_RGM_THRTL (`FLOAT`) {#UUV_RGM_THRTL} +### UUV_PITCH_D (`FLOAT`) {#UUV_PITCH_D} -Throttle gain for manual inputs in rate control mode. +Pitch differential gain. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 10.0 | +|   | | | | 2.0 | -### UUV_RGM_YAW (`FLOAT`) {#UUV_RGM_YAW} +### UUV_PITCH_P (`FLOAT`) {#UUV_PITCH_P} -Yaw gain for manual inputs in rate control mode. +Pitch proportional gain. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 100.0 | +|   | | | | 4.0 | ### UUV_ROLL_D (`FLOAT`) {#UUV_ROLL_D} @@ -40057,70 +36085,6 @@ Roll proportional gain. | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 4.0 | -### UUV_SGM_PITCH (`FLOAT`) {#UUV_SGM_PITCH} - -Pitch gain for manual inputs in attitude control mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.5 | - -### UUV_SGM_ROLL (`FLOAT`) {#UUV_SGM_ROLL} - -Roll gain for manual inputs in attitude control mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.5 | - -### UUV_SGM_THRTL (`FLOAT`) {#UUV_SGM_THRTL} - -Throttle gain for manual inputs in attitude control mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.1 | - -### UUV_SGM_YAW (`FLOAT`) {#UUV_SGM_YAW} - -Yaw gain for manual inputs in attitude control mode. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | | | 0.5 | - -### UUV_SP_MAX_AGE (`FLOAT`) {#UUV_SP_MAX_AGE} - -Maximum time (in seconds) before resetting setpoint. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 2.0 | - -### UUV_STICK_MODE (`INT32`) {#UUV_STICK_MODE} - -Stick mode selector (0=Heave/sway control, roll/pitch leveled; 1=Pitch/roll control). - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 1 | | 0 | - -### UUV_THRUST_SAT (`FLOAT`) {#UUV_THRUST_SAT} - -UUV Thrust setpoint Saturation. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1.0 | | 0.1 | - -### UUV_TORQUE_SAT (`FLOAT`) {#UUV_TORQUE_SAT} - -UUV Torque setpoint Saturation. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0.0 | 1.0 | | 0.3 | - ### UUV_YAW_D (`FLOAT`) {#UUV_YAW_D} Yaw differential gain. @@ -40187,43 +36151,14 @@ Gain of P controller Z. | ------ | -------- | -------- | --------- | ------- | ---- | |   | | | | 1.0 | -### UUV_PGM_VEL (`FLOAT`) {#UUV_PGM_VEL} - -Gain for position control velocity setpoint update. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.5 | - -### UUV_POS_MODE (`INT32`) {#UUV_POS_MODE} - -Stabilization mode(1) or Position Control(0). - -**Values:** - -- `0`: Moves position setpoint in world frame -- `1`: Moves position setpoint in body frame - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 1 | - -### UUV_POS_STICK_DB (`FLOAT`) {#UUV_POS_STICK_DB} - -Deadband for changing position setpoint. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.1 | - ### UUV_STAB_MODE (`INT32`) {#UUV_STAB_MODE} Stabilization mode(1) or Position Control(0). **Values:** -- `0`: Tracks previous attitude setpoint -- `1`: Tracks horizontal attitude (allows yaw change) +- `0`: Position Control +- `1`: Stabilization Mode | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -40346,11 +36281,7 @@ The orientation of the sensor relative to the forward direction of the body fram uXRCE-DDS Agent IP address. -If ethernet is enabled and is the selected configuration for uXRCE-DDS, -the selected Agent IP address will be set and used. -Decimal dot notation is not supported. IP address must be provided -in int32 format. For example, 192.168.1.2 is mapped to -1062731518; -127.0.0.1 is mapped to 2130706433. +If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected Agent IP address will be set and used. Decimal dot notation is not supported. IP address must be provided in int32 format. For example, 192.168.1.2 is mapped to -1062731518; 127.0.0.1 is mapped to 2130706433. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ---------- | ---- | @@ -40396,31 +36327,17 @@ uXRCE-DDS domain ID uXRCE-DDS session key. -uXRCE-DDS key, must be different from zero. -In a single agent - multi client configuration, each client -must have a unique session key. +uXRCE-DDS key, must be different from zero. In a single agent - multi client configuration, each client must have a unique session key. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | | ✓ | | | | 1 | -### UXRCE_DDS_NS_IDX (`INT32`) {#UXRCE_DDS_NS_IDX} - -Define an index-based message namespace. - -Defines an index-based namespace for DDS messages, e.g, uav_0, uav_1, up to uav_9999 -A value less than zero leaves the namespace empty - -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------- | ---- | -| ✓ | -1 | 9999 | | -1 | - ### UXRCE_DDS_PRT (`INT32`) {#UXRCE_DDS_PRT} uXRCE-DDS UDP port. -If ethernet is enabled and is the selected configuration for uXRCE-DDS, -the selected UDP port will be set and used. +If ethernet is enabled and is the selected configuration for uXRCE-DDS, the selected UDP port will be set and used. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -40430,11 +36347,7 @@ the selected UDP port will be set and used. uXRCE-DDS participant configuration. -Set the participant configuration on the Agent's system. -0: Use the default configuration. -1: Restrict messages to localhost -(use in combination with ROS_LOCALHOST_ONLY=1). -2: Use a custom participant with the profile name "px4_participant". +Set the participant configuration on the Agent's system. 0: Use the default configuration. 1: Restrict messages to localhost (use in combination with ROS_LOCALHOST_ONLY=1). 2: Use a custom participant with the profile name "px4_participant". **Values:** @@ -40450,8 +36363,7 @@ Set the participant configuration on the Agent's system. RX rate timeout configuration. -Specifies after how many seconds without receiving data the DDS connection is reestablished. -A value less than one disables the RX rate timeout. +Specifies after how many seconds without receiving data the DDS connection is reestablished. A value less than one disables the RX rate timeout. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -40481,8 +36393,7 @@ When enabled, uxrce_dds_client will synchronize the timestamps of the incoming a TX rate timeout configuration. -Specifies after how many seconds without sending data the DDS connection is reestablished. -A value less than one disables the TX rate timeout. +Specifies after how many seconds without sending data the DDS connection is reestablished. A value less than one disables the TX rate timeout. | Reboot | minValue | maxValue | increment | default | unit | | ------- | -------- | -------- | --------- | ------- | ---- | @@ -40808,7 +36719,7 @@ Time in seconds it takes to tilt form VT_TILT_FW to VT_TILT_MC. ### VT_B_DEC_I (`FLOAT`) {#VT_B_DEC_I} -Backtransition deceleration setpoint to tilt I gain. +Backtransition deceleration setpoint to pitch I gain. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ------- | @@ -40818,8 +36729,7 @@ Backtransition deceleration setpoint to tilt I gain. Approximate deceleration during back transition. -Used to calculate back transition distance in an auto mode. -For standard vtol and tiltrotors a controller is used to track this value during the transition. +Used to calculate back transition distance in an auto mode. For standard vtol and tiltrotors a controller is used to track this value during the transition. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ----- | @@ -40859,12 +36769,7 @@ If set to 1 the control surfaces are locked at the disarmed value in multicopter Use fixed-wing actuation in hover to accelerate forward. -Prevents downforce from pitching the body down when facing wind. -Uses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead. -Only active if demanded pitch is below VT_PITCH_MIN. -Use VT_FWD_THRUST_SC to tune it. -Descend mode is treated as Landing too. -Only active (if enabled) in height-rate controlled modes. +Prevents downforce from pitching the body down when facing wind. Uses puller/pusher (standard VTOL), or forward-tilt (tiltrotor VTOL) to accelerate forward instead. Only active if demanded pitch is below VT_PITCH_MIN. Use VT_FWD_THRUST_SC to tune it. Descend mode is treated as Landing too. Only active (if enabled) in height-rate controlled modes. **Values:** @@ -40884,8 +36789,7 @@ Only active (if enabled) in height-rate controlled modes. Fixed-wing actuation thrust scale in hover. -Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode. -Enabled via VT_FWD_THRUST_EN. +Scale applied to the demanded pitch (below VT_PITCH_MIN) to get the fixed-wing forward actuation in hover mode. Enabled via VT_FWD_THRUST_EN. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -40895,9 +36799,7 @@ Enabled via VT_FWD_THRUST_EN. Differential thrust in forwards flight. -Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. -The effectiveness of differential thrust around the corresponding axis can be -tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y. +Enable differential thrust seperately for roll, pitch, yaw in forward (fixed-wing) mode. The effectiveness of differential thrust around the corresponding axis can be tuned by setting VT_FW_DIFTHR_S_R / VT_FW_DIFTHR_S_P / VT_FW_DIFTHR_S_Y. **Bitmask:** @@ -40943,9 +36845,7 @@ Differential thrust in forward flight is enabled via VT_FW_DIFTHR_EN. Quad-chute altitude. -Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode -and the altitude drops below this altitude (relative altitude above local origin), -it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. +Minimum altitude for fixed-wing flight. When the vehicle is in fixed-wing mode and the altitude drops below this altitude (relative altitude above local origin), it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -40955,9 +36855,7 @@ it will instantly switch back to MC mode and execute behavior defined in COM_QC_ Quad-chute maximum height. -Maximum height above the ground (if available, otherwise above -Home if available, otherwise above the local origin) where triggering a quad-chute is possible. -At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there. +Maximum height above the ground (if available, otherwise above Home if available, otherwise above the local origin) where triggering a quad-chute is possible. At high altitudes there is a big risk to deplete the battery and therefore crash if quad-chuting there. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -40967,9 +36865,7 @@ At high altitudes there is a big risk to deplete the battery and therefore crash Quad-chute max pitch threshold. -Absolute pitch threshold for quad-chute triggering in FW mode. -Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. -Set to 0 do disable this threshold. +Absolute pitch threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -40979,9 +36875,7 @@ Set to 0 do disable this threshold. Quad-chute max roll threshold. -Absolute roll threshold for quad-chute triggering in FW mode. -Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. -Set to 0 do disable this threshold. +Absolute roll threshold for quad-chute triggering in FW mode. Above this the vehicle will transition back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -41009,9 +36903,7 @@ Target throttle value for the transition to fixed-wing flight. Airspeed-less front transition time (open loop). -The duration of the front transition when there is no airspeed feedback available. -When airspeed is used, transition timeout is declared if airspeed does not -reach VT_ARSP_BLEND after this time. +The duration of the front transition when there is no airspeed feedback available. When airspeed is used, transition timeout is declared if airspeed does not reach VT_ARSP_BLEND after this time. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -41021,31 +36913,27 @@ reach VT_ARSP_BLEND after this time. Minimum pitch angle during hover landing. -Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). -During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind. +Overrides VT_PITCH_MIN when the vehicle is in LAND mode (hovering). During landing it can be beneficial to reduce the pitch angle to reduce the generated lift in head wind. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -10.0 | 45.0 | 0.1 | 0.0 | deg | +|   | -10.0 | 45.0 | 0.1 | -5.0 | deg | ### VT_PITCH_MIN (`FLOAT`) {#VT_PITCH_MIN} Minimum pitch angle during hover. -Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if -VT_FWD_TRHUST_EN is set. +Any pitch setpoint below this value is translated to a forward force by the fixed-wing forward actuation if VT_FWD_TRHUST_EN is set. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | -10.0 | 45.0 | 0.1 | 0.0 | deg | +|   | -10.0 | 45.0 | 0.1 | -5.0 | deg | ### VT_PSHER_SLEW (`FLOAT`) {#VT_PSHER_SLEW} Pusher throttle ramp up slew rate. -Defines the slew rate of the puller/pusher throttle during transitions. -Zero will deactivate the slew rate limiting and thus produce an instant throttle -rise to the transition throttle VT_F_TRANS_THR. +Defines the slew rate of the puller/pusher throttle during transitions. Zero will deactivate the slew rate limiting and thus produce an instant throttle rise to the transition throttle VT_F_TRANS_THR. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -41055,11 +36943,7 @@ rise to the transition throttle VT_F_TRANS_THR. Quad-chute uncommanded descent threshold. -Altitude error threshold for quad-chute triggering during fixed-wing flight. -The check is only active if altitude is controlled and the vehicle is below the current altitude reference. -The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current -altitude reference. -Set to 0 do disable. +Altitude error threshold for quad-chute triggering during fixed-wing flight. The check is only active if altitude is controlled and the vehicle is below the current altitude reference. The altitude error is relative to the highest altitude the vehicle has achieved since it has flown below the current altitude reference. Set to 0 do disable. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -41069,12 +36953,7 @@ Set to 0 do disable. Quad-chute transition altitude loss threshold. -Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight -in altitude-controlled flight modes. -Active until 5s after completing transition to fixed-wing. -If the current altitude is more than this value below the altitude at the beginning of the -transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. -Set to 0 do disable this threshold. +Altitude loss threshold for quad-chute triggering during VTOL transition to fixed-wing flight in altitude-controlled flight modes. Active until 5s after completing transition to fixed-wing. If the current altitude is more than this value below the altitude at the beginning of the transition, it will instantly switch back to MC mode and execute behavior defined in COM_QC_ACT. Set to 0 do disable this threshold. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -41234,12 +37113,7 @@ The baud rate (in bits per second) used by the serial port connected with IQUART Module Param - The module's control mechanism. -PWM Mode: Commands a fraction of battery voltage. This changes as the battery voltage changes. -This is the least safe mode because the upper throttle limit is determined by the battery voltage. -Voltage Mode: Commands a voltage. The motor will behave the same way throughout the life of a battery, assuming the commanded voltage is less than the battery voltage. -You must set the MAX_VOLTS parameter. -Velocity Mode: Closed-loop, commands a velocity. The controller will adjust the applied voltage so that the motor spins at the commanded velocity. -This mode has faster reaction times. Only use this if you know the properties of your propeller. You must set the MAX_VELOCITY parameter. +PWM Mode: Commands a fraction of battery voltage. This changes as the battery voltage changes. This is the least safe mode because the upper throttle limit is determined by the battery voltage. Voltage Mode: Commands a voltage. The motor will behave the same way throughout the life of a battery, assuming the commanded voltage is less than the battery voltage. You must set the MAX_VOLTS parameter. Velocity Mode: Closed-loop, commands a velocity. The controller will adjust the applied voltage so that the motor spins at the commanded velocity. This mode has faster reaction times. Only use this if you know the properties of your propeller. You must set the MAX_VELOCITY parameter. **Values:** @@ -41255,8 +37129,7 @@ This mode has faster reaction times. Only use this if you know the properties of The triggered behavior sent to the motors on PX4 disarm. -The behavior triggered when the flight controller disarms. You have the option to trigger your motors' disarm behaviors, set all motors to coast, -or set a predefined throttle setpoint +The behavior triggered when the flight controller disarms. You have the option to trigger your motors' disarm behaviors, set all motors to coast, or set a predefined throttle setpoint **Values:** @@ -41282,8 +37155,7 @@ This is the velocity that will be sent to all motors when PX4 is disarmed and DI Module Param - If the flight controller uses 2D or 3D communication. -The FC and the ESC must agree upon the meaning of the signal coming out of the ESC. When FCs are in 3D mode -they re-map negative signals. This parameter keeps the FC and ESC in agreement. +The FC and the ESC must agree upon the meaning of the signal coming out of the ESC. When FCs are in 3D mode they re-map negative signals. This parameter keeps the FC and ESC in agreement. **Values:** @@ -41356,8 +37228,7 @@ This sets the max pulsing voltage limit when in Voltage Limit Mode. Module Param - 0 = Supply Voltage Mode, 1 = Voltage Limit Mode. -Supply Voltage Mode means that the maximum voltage applied to pulsing is the supplied voltage. Voltage Limit Mode -indicates that PULSE_VOLT_LIM is the maximum allowed voltage to apply towards pulsing. +Supply Voltage Mode means that the maximum voltage applied to pulsing is the supplied voltage. Voltage Limit Mode indicates that PULSE_VOLT_LIM is the maximum allowed voltage to apply towards pulsing. **Values:** @@ -41372,8 +37243,7 @@ indicates that PULSE_VOLT_LIM is the maximum allowed voltage to apply towards pu Reinitialize the target module's values into the PX4 parameters. -Setting this value to true will reinitialize PX4's IQUART connected parameters to the value stored on the currently targeted motor. -This is especially useful if your flight controller powered on before your connected modules +Setting this value to true will reinitialize PX4's IQUART connected parameters to the value stored on the currently targeted motor. This is especially useful if your flight controller powered on before your connected modules | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------------ | ---- | @@ -41492,9 +37362,7 @@ This offsets where the pulse starts around the motor to allow for propeller mech The Module ID of the module you would like to communicate with. -This is the value used as the target module ID of all configuration parameters (not operational parameters). The Vertiq module with the -module ID matching this value will react to all get and set requests from PX4. Any Vertiq client made with dynamic object IDs should -use this value to instantiate itself. +This is the value used as the target module ID of all configuration parameters (not operational parameters). The Vertiq module with the module ID matching this value will react to all get and set requests from PX4. Any Vertiq client made with dynamic object IDs should use this value to instantiate itself. | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | @@ -41544,15 +37412,13 @@ The encoder angle at which theta is zero. Adjust this number to change the locat ### ZENOH_ENABLE (`INT32`) {#ZENOH_ENABLE} -Enable Zenoh. +Zenoh Enable. -Set true (1) to start the Zenoh driver module (a.k.a the "Zenoh-Pico Node"). -See https://docs.px4.io/main/en/middleware/zenoh and -https://docs.px4.io/main/en/modules/modules_driver.html#zenoh +Zenoh -| Reboot | minValue | maxValue | increment | default | unit | -| ------- | -------- | -------- | --------- | ------------ | ---- | -| ✓ | | | | Disabled (0) | +| Reboot | minValue | maxValue | increment | default | unit | +| ------- | -------- | -------- | --------- | ------- | ---- | +| ✓ | | | | 0 | ## Miscellaneous @@ -41622,18 +37488,15 @@ Lightware SF1xx/SF20/LW20 Operation Mode. | ------ | -------- | -------- | --------- | ------- | ---- | |   | 0 | 2 | | 1 | -### SPC_VEHICLE_RESP (`FLOAT`) {#SPC_VEHICLE_RESP} +### UUV_SKIP_CTRL (`INT32`) {#UUV_SKIP_CTRL} -SPC_VEHICLE_RESP. - -| Reboot | minValue | maxValue | increment | default | unit | -| ------ | -------- | -------- | --------- | ------- | ---- | -|   | | | | 0.5 | +Skip the controller. -### ZENOH_DOMAIN_ID (`INT32`) {#ZENOH_DOMAIN_ID} +**Values:** -ROS2 RMW_ZENOH_CPP Domain id. +- `0`: use the module's controller +- `1`: skip the controller and feedthrough the setpoints | Reboot | minValue | maxValue | increment | default | unit | | ------ | -------- | -------- | --------- | ------- | ---- | -|   | 0 | 232 | | 0 | +|   | | | | 0 | diff --git a/docs/en/companion_computer/ark_jetson_pab_carrier.md b/docs/en/companion_computer/ark_jetson_pab_carrier.md index ffb7931a7b02..33463f5ca0f0 100644 --- a/docs/en/companion_computer/ark_jetson_pab_carrier.md +++ b/docs/en/companion_computer/ark_jetson_pab_carrier.md @@ -12,19 +12,16 @@ The [ARK Jetson Pixhawk Autopilot Bus (PAB) Carrier](https://arkelectron.gitbook ## Specifications - **Power Requirements** - - 5V - 4A minimum (dependent on usage and peripherals) - **Additional Features** - - Pixhawk Autopilot Bus (PAB) Form Factor ([PAB Standard](https://github.com/pixhawk/Pixhawk-Standards/blob/master/DS-010%20Pixhawk%20Autopilot%20Bus%20Standard.pdf)) - MicroSD Slot - USA-built, NDAA compliant - Integrated 1W heater for sensor stability in extreme conditions - **Physical Details** - - Weight: - Without Jetson and Flight Controller – 80g - With Jetson, no heatsink or Flight Controller – 108g diff --git a/docs/en/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md b/docs/en/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md index 3cdab57030c7..565b68eebba3 100644 --- a/docs/en/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md +++ b/docs/en/companion_computer/holybro_pixhawk_rpi_cm4_baseboard.md @@ -18,7 +18,6 @@ The board follows the [Pixhawk Connector Standard](https://github.com/pixhawk/Pi - [Holybro Pixhawk RPi CM4 Baseboard](https://holybro.com/products/pixhawk-rpi-cm4-baseboard) (www.holybro.com) The baseboard can be purchased with or without an RPi CM4 and/or flight controller: - - The Raspberry Pi CM4 (CM4008032) supplied by Holybro has the following specification: - RAM: 8GB - eMMC: 32GB @@ -167,7 +166,6 @@ To enable this MAVLink instance on the FC: ![Image of baseboard showing FC USB-C connector](../../assets/companion_computer/holybro_pixhawk_rpi_cm4_baseboard/baseboard_fc_usb_c.jpg) 1. [Set the parameters](../advanced_config/parameters.md): - - `MAV_1_CONFIG` = `102` - `MAV_1_MODE = 2` - `SER_TEL2_BAUD` = `921600` @@ -180,7 +178,6 @@ On the RPi side: 1. Connect to the RPi (using WiFi, a router, or a WiFi Dongle). 1. Enable the RPi serial port by running `RPi-config` - - Go to `3 Interface Options`, then `I6 Serial Port`. Then choose: - `login shell accessible over serial → No` diff --git a/docs/en/companion_computer/pixhawk_rpi.md b/docs/en/companion_computer/pixhawk_rpi.md index 218a48c3a2a9..b998f897a1a9 100644 --- a/docs/en/companion_computer/pixhawk_rpi.md +++ b/docs/en/companion_computer/pixhawk_rpi.md @@ -91,7 +91,7 @@ During PX4 setup and configuration the USB connection with your ground station l These instructions work on PX4 v1.14 and later. -If you need to update the firmware then connect the Pixhawk to your laptop/desktop via the `USB` port and use QGroundControl to update the firmware as described [Firmware > Install Stable PX4](../config/firmware.md#install-stable-px4). +If you need to update the firmware then connect the Pixhawk to your laptop/desktop via the `USB` port and use QGroundControl to update the firmware as described [Firmware > Install Stable PX4](../config/firmware.md#install-stable-px4). If you want the latest developer version then update the firmware to the "main" as described in [Firmware > Installing PX4 Master, Beta or Custom Firmware](../config/firmware.md#installing-px4-main-beta-or-custom-firmware). ::: info @@ -143,7 +143,6 @@ Enter the following commands (in sequence) a terminal to configure Ubuntu for RP ``` 1. Go to the **Interface Option** and then click **Serial Port**. - - Select **No** to disable serial login shell. - Select **Yes** to enable the serial interface. - Click **Finish** and restart the RPi. @@ -162,7 +161,6 @@ Enter the following commands (in sequence) a terminal to configure Ubuntu for RP ``` 1. Then save the file and restart the RPi. - - In `nano` you can save the file using the following sequence of keyboard shortcuts: **ctrl+x**, **ctrl+y**, **Enter**. 1. Check that the serial port is available. diff --git a/docs/en/computer_vision/collision_prevention.md b/docs/en/computer_vision/collision_prevention.md index d2ebb4597a06..1fad93be3df1 100644 --- a/docs/en/computer_vision/collision_prevention.md +++ b/docs/en/computer_vision/collision_prevention.md @@ -60,7 +60,7 @@ Configure collision prevention by [setting the following parameters](../advanced | [CP_DELAY](../advanced_config/parameter_reference.md#CP_DELAY) | Set the sensor and velocity setpoint tracking delay. See [Delay Tuning](#delay_tuning) below. | | [CP_GUIDE_ANG](../advanced_config/parameter_reference.md#CP_GUIDE_ANG) | Set the angle (to both sides of the commanded direction) within which the vehicle may deviate if it finds fewer obstacles in that direction. See [Guidance Tuning](#angle_change_tuning) below. | | [CP_GO_NO_DATA](../advanced_config/parameter_reference.md#CP_GO_NO_DATA) | Set to 1 to allow the vehicle to move in directions where there is no sensor coverage (default is 0/`False`). | -| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Must be set to `Acceleration based`. | +| [MPC_POS_MODE](../advanced_config/parameter_reference.md#MPC_POS_MODE) | Must be set to `Acceleration based`. | ## Algorithm Description @@ -213,7 +213,6 @@ The steps are: 3. Open PlotJuggler and navigate to the **Tools > Reactive Script Editor** section. In the **Script Editor** tab, add following scripts in the appropriate sections: - - **Global code, executed once:** ```lua diff --git a/docs/en/concept/flight_tasks.md b/docs/en/concept/flight_tasks.md index fad2dca6feca..242a1e96fe53 100644 --- a/docs/en/concept/flight_tasks.md +++ b/docs/en/concept/flight_tasks.md @@ -32,7 +32,6 @@ The instructions below might be used to create a task named _MyTask_: - FlightTaskMyTask.hpp - FlightTaskMyTask.cpp 3. Update **CMakeLists.txt** for the new task - - Copy the contents of the **CMakeLists.txt** for another task - e.g. [Orbit/CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/flight_mode_manager/tasks/Orbit/CMakeLists.txt) - Update the copyright to the current year @@ -135,7 +134,6 @@ The instructions below might be used to create a task named _MyTask_: Usually a parameter is used to select when a particular flight task should be used. For example, to enable our new `MyTask` in multicopter Position mode: - - Update `MPC_POS_MODE` ([multicopter_position_mode_params.c](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/mc_pos_control/multicopter_position_mode_params.c)) to add an option for selecting "MyTask" if the parameter has a previously unused value like 5: ```c diff --git a/docs/en/concept/sd_card_layout.md b/docs/en/concept/sd_card_layout.md index 648614e1ea69..e379dee52ae2 100644 --- a/docs/en/concept/sd_card_layout.md +++ b/docs/en/concept/sd_card_layout.md @@ -14,7 +14,7 @@ The directory structure/layout is shown below. | `/etc/` | Extra config. See [System Startup > Replacing the System Startup][replace system start]. | | `/log/` | Full [flight logs](../dev_log/logging.md) | | `/mission_log/` | Reduced flight logs | -| `/fw/` | [DroneCAN](../dronecan/index.md) firmware | +| `/fw/` | [DroneCAN](../dronecan/index.md) firmware | | `/uavcan.db/` | DroneCAN DNA server DB + logs | | `/params` | Parameters (if not in FRAM/FLASH) | | `/dataman` | Mission storage file | diff --git a/docs/en/config/_autotune.md b/docs/en/config/_autotune.md index b6b8dedd6983..38eb200e95d7 100644 --- a/docs/en/config/_autotune.md +++ b/docs/en/config/_autotune.md @@ -82,7 +82,6 @@ The test steps are: If an [Enable/Disable Autotune Switch](#enable-disable-autotune-switch) is configured you can just toggle the switch to the "enabled" position. - 1. In QGroundControl, open the menu **Vehicle setup > PID Tuning**: ![Tuning Setup > Autotune Enabled](../../assets/qgc/setup/autotune/autotune.png) @@ -197,11 +196,8 @@ By default, the autotune maneuvers ensure that a sufficient angular rate is reac If the signal-to-noise ratio of the vehicle is low, the system identification algorithm might have issues finding the correct coefficients. Ensure that there is no excessive noise and/or platform vibration. - - - ### The drone oscillates after auto-tuning Due to effects not included in the mathematical model such as delays, saturation, slew-rate, airframe flexibility, the loop gain can be too high. diff --git a/docs/en/config/flight_mode.md b/docs/en/config/flight_mode.md index 545f1a2acc15..71be6f199068 100644 --- a/docs/en/config/flight_mode.md +++ b/docs/en/config/flight_mode.md @@ -4,15 +4,15 @@ This topic explains how to map [flight modes](../getting_started/px4_basic_conce :::tip In order to set up flight modes you must already have: + - [Configured your radio](../config/radio.md) - [Setup your transmitter](#rc-transmitter-setup) to encode the physical positions of your mode switch(es) into a single channel. - We provide examples for the popular *Taranis* transmitter [below](#taranis-setup-3-way-switch-configuration-for-single-channel-mode) (check your documentation if you use a different transmitter). -::: - + We provide examples for the popular _Taranis_ transmitter [below](#taranis-setup-3-way-switch-configuration-for-single-channel-mode) (check your documentation if you use a different transmitter). + ::: ## What Flight Modes and Switches Should I Set? -Flight Modes provide different types of *autopilot-assisted flight*, and *fully autonomous flight*. +Flight Modes provide different types of _autopilot-assisted flight_, and _fully autonomous flight_. You can set any (or none) of the flight modes [available to your vehicle](../flight_modes/index.md#flight-modes). Most users should set the following modes and functions, as these make the vehicle easier and safer to fly: @@ -33,26 +33,25 @@ You can also separately specify channels for mapping a kill switch, return to la To configure single-channel flight mode selection: -1. Start *QGroundControl* and connect the vehicle. +1. Start _QGroundControl_ and connect the vehicle. 1. Turn on your RC transmitter. 1. Select **"Q" icon > Vehicle Setup > Flight Modes** (sidebar) to open _Flight Modes Setup_. ![Flight modes single-channel](../../assets/qgc/setup/flight_modes/flight_modes_single_channel.jpg) -1. Specify *Flight Mode Settings*: - * Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). - * Move the transmitter switch (or switches) that you have set up for mode selection through the available positions. - The mode slot matching your current switch position will be highlighted (above this is *Flight Mode 1*). +1. Specify _Flight Mode Settings_: + - Select the **Mode channel** (above this shown as Channel 5, but this will depend on your transmitter configuration). + - Move the transmitter switch (or switches) that you have set up for mode selection through the available positions. + The mode slot matching your current switch position will be highlighted (above this is _Flight Mode 1_). ::: info While you can set flight modes in any of the 6 slots, only the channels that are mapped to switch positions will be highlighted/used. ::: - * Select the flight mode that you want triggered for each switch position. -1. Specify *Switch Settings*: - * Select the channels that you want to map to specific actions - e.g.: *Return* mode, *Kill switch*, *offboard* mode, etc. (if you have spare switches and channels on your transmitter). - + - Select the flight mode that you want triggered for each switch position. +1. Specify _Switch Settings_: + - Select the channels that you want to map to specific actions - e.g.: _Return_ mode, _Kill switch_, _offboard_ mode, etc. (if you have spare switches and channels on your transmitter). 1. Test that the modes are mapped to the right transmitter switches: - * Check the *Channel Monitor* to confirm that the expected channel is changed by each switch. - * Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on *QGroundControl* for the active mode). + - Check the _Channel Monitor_ to confirm that the expected channel is changed by each switch. + - Select each mode switch on your transmitter in turn, and check that the desired flight mode is activated (the text turns yellow on _QGroundControl_ for the active mode). All values are automatically saved as they are changed. @@ -61,7 +60,6 @@ All values are automatically saved as they are changed. This section contains a small number of possible setup configurations for taranis. QGroundControl _may_ have [setup information for other transmitters here](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/flight_modes.html#transmitter-setup). - ### Taranis Setup: 3-way Switch Configuration for Single-Channel Mode @@ -70,7 +68,7 @@ If you only need to support selecting between two or three modes then you can ma Below we show how to map the Taranis 3-way "SD" switch to channel 5. ::: info -This example shows how to set up the popular *FrSky Taranis* transmitter. +This example shows how to set up the popular _FrSky Taranis_ transmitter. Transmitter setup will be different on other transmitters. ::: @@ -78,15 +76,14 @@ Open the Taranis UI **MIXER** page and scroll down to **CH5**, as shown below: ![Taranis - Map channel to switch](../../assets/qgc/setup/flight_modes/single_channel_mode_selection_1.png) -Press **ENT(ER)** to edit the **CH5** configuration then change the **Source** to be the *SD* button. +Press **ENT(ER)** to edit the **CH5** configuration then change the **Source** to be the _SD_ button. ![Taranis - Configure channel](../../assets/qgc/setup/flight_modes/single_channel_mode_selection_2.png) That's it! Channel 5 will now output 3 different PWM values for the three different **SD** switch positions. -The *QGroundControl* configuration is then as described in the previous section. - +The _QGroundControl_ configuration is then as described in the previous section. ### Taranis Setup: Multi-Switch Configuration for Single-Channel Mode @@ -96,19 +93,18 @@ Commonly this is done by encoding the positions of a 2- and a 3-position switch On the FrSky Taranis this process involves assigning a "logical switch" to each combination of positions of the two real switches. Each logical switch is then assigned to a different PWM value on the same channel. -The video below shows how this is done with the *FrSky Taranis* transmitter. +The video below shows how this is done with the _FrSky Taranis_ transmitter. -The *QGroundControl* configuration is then [as described above](#flight-mode-selection). - +The _QGroundControl_ configuration is then [as described above](#flight-mode-selection). ## Further Information -* [Flight Modes Overview](../flight_modes/index.md) -* [QGroundControl > Flight Modes](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/flight_modes.html#px4-pro-flight-mode-setup) -* [PX4 Setup Video - @6m53s](https://youtu.be/91VGmdSlbo4?t=6m53s) (Youtube) -* [Radio switch parameters](../advanced_config/parameter_reference.md#radio-switches) - Can be used to set mappings via parameters +- [Flight Modes Overview](../flight_modes/index.md) +- [QGroundControl > Flight Modes](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/setup_view/flight_modes.html#px4-pro-flight-mode-setup) +- [PX4 Setup Video - @6m53s](https://youtu.be/91VGmdSlbo4?t=6m53s) (Youtube) +- [Radio switch parameters](../advanced_config/parameter_reference.md#radio-switches) - Can be used to set mappings via parameters diff --git a/docs/en/config/level_horizon_calibration.md b/docs/en/config/level_horizon_calibration.md index 6eb708b16a25..30c2fc0a71c3 100644 --- a/docs/en/config/level_horizon_calibration.md +++ b/docs/en/config/level_horizon_calibration.md @@ -18,7 +18,6 @@ To level the horizon: You should already have set the [Autopilot Orientation](../config/flight_controller_orientation.md). If not, you can also set it here. ::: 1. Place the vehicle in its level flight orientation on a level surface: - - For planes this is the position during level flight (planes tend to have their wings slightly pitched up!) - For copters this is the hover position. diff --git a/docs/en/config/safety.md b/docs/en/config/safety.md index 9f72f4589ff9..f8a224f94535 100644 --- a/docs/en/config/safety.md +++ b/docs/en/config/safety.md @@ -128,10 +128,10 @@ Additional (and underlying) parameter settings are shown below. | Parameter | Setting | Description | | ----------------------------------------------------------------------------------------------------- | --------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. | +| [COM_RC_LOSS_T](../advanced_config/parameter_reference.md#COM_RC_LOSS_T) | Manual Control Loss Timeout | Time after last setpoint received from the selected manual control source after which manual control is considered lost. This must be kept short because the vehicle will continue to fly using the last known stick position until the timeout triggers. | | [COM_FAIL_ACT_T](../advanced_config/parameter_reference.md#COM_FAIL_ACT_T) | Failsafe Reaction Delay | Delay in seconds between failsafe condition being triggered (`COM_RC_LOSS_T`) and failsafe action (RTL, Land, Hold). In this state the vehicle waits in hold mode for the manual control source to reconnect. This might be set longer for long-range flights so that intermittent connection loss doesn't immediately invoke the failsafe. It can be to zero so that the failsafe triggers immediately. | | [NAV_RCL_ACT](../advanced_config/parameter_reference.md#NAV_RCL_ACT) | Failsafe Action | Disabled, Loiter, Return, Land, Disarm, Terminate. | -| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC Loss Exceptions | Set modes in which manual control loss is ignored. | +| [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT) | RC Loss Exceptions | Set modes in which manual control loss is ignored. | ## Data Link Loss Failsafe @@ -142,11 +142,11 @@ Users that want to disable this failsafe in specific modes can do so using the p The settings and underlying parameters are shown below. -| Setting | Parameter | Description | -| ---------------------- | ------------------------------------------------------------------------ | --------------------------------------------------------------------------------- | -| Data Link Loss Timeout | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Amount of time after losing the data connection before the failsafe will trigger. | -| Failsafe Action | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. | -| Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. | +| Setting | Parameter | Description | +| ----------------------------------------------------------- | -------------------------------------------------------------------------- | --------------------------------------------------------------------------------- | +| Data Link Loss Timeout | [COM_DL_LOSS_T](../advanced_config/parameter_reference.md#COM_DL_LOSS_T) | Amount of time after losing the data connection before the failsafe will trigger. | +| Failsafe Action | [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT) | Disabled, Hold mode, Return mode, Land mode, Disarm, Terminate. | +| Mode exceptions for DLL failsafe | [COM_DLL_EXCEPT](../advanced_config/parameter_reference.md#COM_DLL_EXCEPT) | Set modes in which data link loss is ignored. | ## Geofence Failsafe diff --git a/docs/en/config/safety_intro.md b/docs/en/config/safety_intro.md index 771f113d7306..2c4fdeec334e 100644 --- a/docs/en/config/safety_intro.md +++ b/docs/en/config/safety_intro.md @@ -13,7 +13,7 @@ These are covered in the following topics: - [Safe Points (Rally)](../flying/plan_safety_points.md) - [Prearm/Arm/Disarm Configuration](../advanced_config/prearm_arm_disarm.md) - [Flight Termination Configuration](../advanced_config/flight_termination.md) -- [First Flight Guidelines](../flying/first_flight_guidelines.md) +- [First Flight Guidelines](../flying/first_flight_guidelines.md) ::: tip Note that the [First Flight Guidelines](../flying/first_flight_guidelines.md) are listed _last_. diff --git a/docs/en/config_heli/index.md b/docs/en/config_heli/index.md index 131f1c7e70ad..d74e4c8d79eb 100644 --- a/docs/en/config_heli/index.md +++ b/docs/en/config_heli/index.md @@ -42,14 +42,12 @@ To setup and configure a helicopter: ![Geometry: helicopter](../../assets/config/actuators/qgc_geometry_helicopter.png) The motors have no configurable geometry: - - `Rotor (Motor 1)`: The main rotor - `Yaw tail motor (Motor 2)`: The tail rotor Swash plate servos: `3` | `4` For each servo set: - - `Angle`: Clockwise angle in degree on the swash plate circle at which the servo arm is attached starting from `0` pointing forwards. Example for a typical setup where three servos are controlling the swash plate equally distributed over the circle (360° / 3 =) 120° apart each which results in the angles: @@ -65,7 +63,6 @@ To setup and configure a helicopter: - `Trim`: Offset individual servo positions. This is only needed in rare case when the swash plate is not level even though all servos are centered. Additional settings: - - `Yaw compensation scale based on collective pitch`: How much yaw is feed forward compensated based on the current collective pitch. - `Main rotor turns counter-clockwise`: `Disabled` (clockwise rotation) | `Enabled` - `Throttle spoolup time`: Set value (in seconds) greater than the achievable minimum motor spool up time. @@ -73,12 +70,10 @@ To setup and configure a helicopter: 1. Remove the rotor blades and propellers 1. Assign motors and servos to outputs and test (also in [Actuator configuration](../config/actuators.md)): - 1. Assign the [motors and servos to the outputs](../config/actuators.md#actuator-outputs). 1. Power the vehicle with a battery and use the [actuator testing sliders](../config/actuators.md#actuator-testing) to validate correct servo and motor assignment and direction. 1. Using an RC in [Acro mode](../flight_modes_mc/acro.md), verify the correct movement of the swash-plate. With most airframes you need to see the following: - - Moving the roll stick to the right should tilt the swash-plate to the right. - Moving the pitch stick forward should tilt the swash-plate forward. @@ -144,7 +139,6 @@ The rate controller should be tuned in [Acro mode](../flight_modes_mc/acro.md), 3. Then enable the PID gains. Start off with following values: - - [MC_ROLLRATE_P](../advanced_config/parameter_reference.md#MC_ROLLRATE_P), [MC_PITCHRATE_P](../advanced_config/parameter_reference.md#MC_PITCHRATE_P) a quarter of the value you found to work well as the corresponding feed forward value in the previous step. `P = FF / 4` ```sh diff --git a/docs/en/config_mc/index.md b/docs/en/config_mc/index.md index 9d15f9924ef7..db4fd6809a77 100644 --- a/docs/en/config_mc/index.md +++ b/docs/en/config_mc/index.md @@ -123,14 +123,12 @@ Tuning is the final step, carried out only after most other setup and configurat ::: info Automatic tuning works on frames that have reasonable authority and dynamics around all the body axes. It has primarily been tested on racing quads and X500, and is expected to be less effective on tricopters with a tiltable rotor. - + Manual tuning using these guides are only needed if there is a problem with autotune: - - [MC PID Tuning (Manual/Basic)](../config_mc/pid_tuning_guide_multicopter_basic.md) — Manual tuning basic how to. - [MC PID Tuning Guide (Manual/Detailed)](../config_mc/pid_tuning_guide_multicopter.md) — Manual tuning with detailed explanation. - - ::: + ::: - [MC Filter/Control Latency Tuning](../config_mc/filter_tuning.md) — Trade off control latency and noise filtering. - [MC Setpoint Tuning (Trajectory Generator)](../config_mc/mc_trajectory_tuning.md) diff --git a/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md b/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md index 1faf538b8f70..dcadf60b94e5 100644 --- a/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md +++ b/docs/en/config_mc/pid_tuning_guide_multicopter_basic.md @@ -46,7 +46,6 @@ Then adjust the sliders (as discussed below) to improve the tracking of the resp These need to be set low, but such that the **motors never stop** when the vehicle is armed. This can be tested in [Acro mode](../flight_modes_mc/acro.md) or in [Stabilized mode](../flight_modes_mc/manual_stabilized.md): - - Remove propellers - Arm the vehicle and lower the throttle to the minimum - Tilt the vehicle to all directions, about 60 degrees @@ -77,7 +76,6 @@ The tuning procedure is: As a result, the optimal tuning at hover thrust may not be ideal when the vehicle is operating at higher thrust. The thrust curve value can be used to compensate for this non-linearity: - - For PWM controllers, 0.3 is a good default (which may benefit from [further tuning](../config_mc/pid_tuning_guide_multicopter.md#thrust-curve)). - For RPM-based controllers, use 1 (no further tuning is required as these have a quadratic thrust curve). @@ -120,7 +118,6 @@ The tuning procedure is: ::: 1. Repeat the tuning process for the attitude controller on all the axes. 1. Repeat the tuning process for the velocity and positions controllers (on all the axes). - - Use Position mode when tuning these controllers - Select the **Simple position control** option in the _Position control mode ..._ selector (this allows direct control for the generation of step inputs) diff --git a/docs/en/config_rover/rate_tuning.md b/docs/en/config_rover/rate_tuning.md index 92d4ea5d9884..fd327d34efc9 100644 --- a/docs/en/config_rover/rate_tuning.md +++ b/docs/en/config_rover/rate_tuning.md @@ -15,13 +15,11 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun Small rovers especially can be prone to rolling over when steering aggressively at high speeds. If this is the case: - 1. In [Acro mode](../flight_modes_rover/manual.md#acro-mode), set [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) to a small value, drive the rover at full throttle and steer all the way to the left or right. 2. Increase [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) until the wheels of the rover start to lift up. 3. Set [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM) to the highest value that does not cause the rover to lift up. If you see no need to limit the yaw rate, set this parameter to the maximum yaw rate the rover can achieve: - 1. In [Manual mode](../flight_modes_rover/manual.md#manual-mode) drive the rover at full throttle and with the maximum steering angle. 2. Plot the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) and enter the highest observed value for [RO_YAW_RATE_LIM](#RO_YAW_RATE_LIM). @@ -51,7 +49,6 @@ Configure the following [parameters](../advanced_config/parameters.md) in QGroun :::tip To tune this parameter: - 1. Put the rover in [Acro mode](../flight_modes_rover/manual.md#acro-mode) and hold the throttle stick and the right stick at a few different levels for a couple of seconds each. 1. Disarm the rover and from the flight log plot the `adjusted_yaw_rate_setpoint` and the `measured_yaw_rate` from [RoverRateStatus](../msg_docs/RoverRateStatus.md) over each other. 1. Increase [RO_YAW_RATE_P](#RO_YAW_RATE_P) if the measured value does not track the setpoint fast enough or decrease it if the measurement overshoots the setpoint by too much. diff --git a/docs/en/config_vtol/vtol_ice_shedding.md b/docs/en/config_vtol/vtol_ice_shedding.md index 629a599f93e4..bf9ccc80afd3 100644 --- a/docs/en/config_vtol/vtol_ice_shedding.md +++ b/docs/en/config_vtol/vtol_ice_shedding.md @@ -14,7 +14,8 @@ seconds. In each cycle, the rotors are spun for two seconds at a motor output of :::warning When enabling the feature on a new airframe, there is the risk of producing torques that disturb the fixed-wing rate controller. To mitigate this risk: - - Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually - produces 1% thrust - - Be prepared to take control and switch back to multicopter -::: + +- Set your `PWM_MIN` values correctly, so that the motor output 0.01 actually + produces 1% thrust +- Be prepared to take control and switch back to multicopter + ::: diff --git a/docs/en/config_vtol/vtol_without_airspeed_sensor.md b/docs/en/config_vtol/vtol_without_airspeed_sensor.md index 758543c354f5..dbcfc56ec23f 100644 --- a/docs/en/config_vtol/vtol_without_airspeed_sensor.md +++ b/docs/en/config_vtol/vtol_without_airspeed_sensor.md @@ -66,7 +66,7 @@ Set the minimum front transition time ([VT_TRANS_MIN_TM](../advanced_config/para Because the risk of stalling is real, it is recommended to set the 'fixed-wing minimum altitude' (a.k.a. 'quad-chute') threshold ([VT_FW_MIN_ALT](../advanced_config/parameter_reference.md#VT_FW_MIN_ALT)). -This will cause the VTOL to transition back to multicopter mode and initiate the [Return mode](../flight_modes_vtol/return.md) below a certain altitude. +This will cause the VTOL to transition back to multicopter mode and initiate the [Return mode](../flight_modes_vtol/return.md) below a certain altitude. You could set this to 15 or 20 meters to give the multicopter time to recover from a stall. The position estimator tested for this mode is EKF2, which is enabled by default (for more information see [Switching State Estimators](../advanced/switching_state_estimators.md#how-to-enable-different-estimators) and [EKF2_EN ](../advanced_config/parameter_reference.md#EKF2_EN)). diff --git a/docs/en/dev_airframes/adding_a_new_frame.md b/docs/en/dev_airframes/adding_a_new_frame.md index addec0b1329d..f34ec3ea3071 100644 --- a/docs/en/dev_airframes/adding_a_new_frame.md +++ b/docs/en/dev_airframes/adding_a_new_frame.md @@ -306,7 +306,6 @@ If the airframe is for a **new group** you additionally need to: ``` 1. Update _QGroundControl_: - - Add the svg image for the group into: [src/AutopilotPlugins/Common/images](https://github.com/mavlink/qgroundcontrol/tree/master/src/AutoPilotPlugins/Common/Images) - Add reference to the svg image into [qgcimages.qrc](https://github.com/mavlink/qgroundcontrol/blob/master/qgcimages.qrc), following the pattern below: diff --git a/docs/en/dev_log/logging.md b/docs/en/dev_log/logging.md index 47d4d6f385ba..daa0d6d9e7ad 100644 --- a/docs/en/dev_log/logging.md +++ b/docs/en/dev_log/logging.md @@ -33,12 +33,12 @@ The logging system is configured by default to collect sensible logs for [flight Logging may further be configured using the [SD Logging](../advanced_config/parameter_reference.md#sd-logging) parameters. The parameters you are most likely to change are listed below. -| Parameter | Description | -| ------------------------------------------------------------------------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| Parameter | Description | +| ------------------------------------------------------------------------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | | [SDLOG_MODE](../advanced_config/parameter_reference.md#SDLOG_MODE) | Logging Mode. Defines when logging starts and stops.
- `0`: Log when armed until disarm (default).
- `1`: Log from boot until disarm.
- `2`: Log from boot until shutdown.
- `3`: Log based on the [AUX1 RC channel](../advanced_config/parameter_reference.md#RC_MAP_AUX1).
- `4`: Log from first armed until shutdown. | -| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. -| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | -| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | +| [SDLOG_BACKEND](../advanced_config/parameter_reference.md#SDLOG_BACKEND) | Logging Backend (bitmask). Setting a bit enables the corresponding backend. If no backend is selected, the logger is disabled.
- bit `0`: SD card logging.
- bit `1`: Mavlink logging. | +| [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) | Logging profile. Use this to enable less common logging/analysis (e.g. for EKF2 replay, high rate logging for PID & filter tuning, thermal temperature calibration). | +| [SDLOG_MISSION](../advanced_config/parameter_reference.md#SDLOG_MISSION) | Create very small additional "Mission Log".
This log can _not_ be used with [Flight Review](../log/flight_log_analysis.md#flight-review-online-tool), but is useful when you need a small log for geotagging or regulatory compliance. | Useful settings for specific cases: diff --git a/docs/en/dev_setup/building_px4.md b/docs/en/dev_setup/building_px4.md index d9ac63b279c4..b5ab7ccdc329 100644 --- a/docs/en/dev_setup/building_px4.md +++ b/docs/en/dev_setup/building_px4.md @@ -39,8 +39,8 @@ Navigate into the **PX4-Autopilot** directory and start [Gazebo SITL](../sim_gaz make px4_sitl gz_x500 ``` -::: details If you installed Gazebo Classic -Start [Gazebo Classic SITL](../sim_gazebo_classic/index.md) using the following command: +::: details If you installed Gazebo Classic +Start [Gazebo Classic SITL](../sim_gazebo_classic/index.md) using the following command: ```sh make px4_sitl gazebo-classic diff --git a/docs/en/dev_setup/config_initial.md b/docs/en/dev_setup/config_initial.md index 1e29ed30c636..f636aef195bb 100644 --- a/docs/en/dev_setup/config_initial.md +++ b/docs/en/dev_setup/config_initial.md @@ -18,7 +18,6 @@ The equipment below is highly recommended: ::: info The listed computers have acceptable performance, but a more recent and powerful computer is recommended. ::: - - Lenovo Thinkpad with i5-core running Windows 11 - MacBook Pro (early 2015 and later) with macOS 10.15 or later - Lenovo Thinkpad i5 with Ubuntu Linux 20.04 or later diff --git a/docs/en/dev_setup/dev_env.md b/docs/en/dev_setup/dev_env.md index 33069072c632..b57ab037c0af 100644 --- a/docs/en/dev_setup/dev_env.md +++ b/docs/en/dev_setup/dev_env.md @@ -11,13 +11,13 @@ The _supported platforms_ for PX4 development are: The table below shows what PX4 targets you can build on each OS. | Target | Linux (Ubuntu) | macOS | Windows | -| -------------------------------------------------------------------------------------------------------------------------------------- | :------------: | :-: | :-----: | -| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | -| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | -| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | -| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | -| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | +| -------------------------------------------------------------------------------------------------------------------------------------- | :------------: | :---: | :-----: | +| **NuttX based hardware:** [Pixhawk Series](../flight_controller/pixhawk_series.md), [Crazyflie](../complete_vehicles_mc/crazyflie2.md) | ✓ | ✓ | ✓ | +| **Linux-based hardware:** [Raspberry Pi 2/3](../flight_controller/raspberry_pi_navio2.md) | ✓ | | | +| **Simulation:** [Gazebo SITL](../sim_gazebo_gz/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [Gazebo Classic SITL](../sim_gazebo_classic/index.md) | ✓ | ✓ | ✓ | +| **Simulation:** [ROS with Gazebo Classic](../simulation/ros_interface.md) | ✓ | | ✓ | +| **Simulation:** ROS 2 with Gazebo | ✓ | | ✓ | Experienced Docker users can also build with the containers used by our continuous integration system: [Docker Containers](../test_and_ci/docker.md) diff --git a/docs/en/dev_setup/dev_env_mac.md b/docs/en/dev_setup/dev_env_mac.md index fee66f554e79..25757f8657b4 100644 --- a/docs/en/dev_setup/dev_env_mac.md +++ b/docs/en/dev_setup/dev_env_mac.md @@ -107,7 +107,6 @@ To setup the environment for [Gazebo Classic](../sim_gazebo_classic/index.md) si sh macos.sh ``` - ## Next Steps Once you have finished setting up the command-line toolchain: diff --git a/docs/en/dev_setup/vscode.md b/docs/en/dev_setup/vscode.md index fb4d9e79e3b4..302e68b250cd 100644 --- a/docs/en/dev_setup/vscode.md +++ b/docs/en/dev_setup/vscode.md @@ -23,7 +23,6 @@ You must already have installed the command line [PX4 developer environment](../ 1. [Download and install VSCode](https://code.visualstudio.com/) (you will be offered the correct version for your OS). 1. Open VSCode and add the PX4 source code: - - Select _Open folder ..._ option on the welcome page (or using the menu: **File > Open Folder**): ![Open Folder](../../assets/toolchain/vscode/welcome_open_folder.jpg) @@ -45,7 +44,6 @@ You must already have installed the command line [PX4 developer environment](../ :::tip If the prompts disappear, click the little "alarm" icon on the right of the bottom blue bar. ::: - - If prompted to install a new version of _cmake_: - Say **No** (the right version is installed with the [PX4 developer environment](../dev_setup/dev_env.md)). - If prompted to sign into _github.com_ and add your credentials: @@ -59,7 +57,6 @@ You must already have installed the command line [PX4 developer environment](../ To build: 1. Select your build target ("cmake build config"): - - The current _cmake build target_ is shown on the blue _config_ bar at the bottom (if this is already your desired target, skip to next step). ![Select Cmake build target](../../assets/toolchain/vscode/cmake_build_config.jpg) diff --git a/docs/en/dronecan/ark_cannode.md b/docs/en/dronecan/ark_cannode.md index e1fca0c6d7ca..fdb403f71753 100644 --- a/docs/en/dronecan/ark_cannode.md +++ b/docs/en/dronecan/ark_cannode.md @@ -83,10 +83,10 @@ This is done using the the parameters named like `UAVCAN_SUB_*` in the parameter On the ARK CANnode, you may need to configure the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_flow.md b/docs/en/dronecan/ark_flow.md index 8b43846bd33f..c3c7906c87ed 100644 --- a/docs/en/dronecan/ark_flow.md +++ b/docs/en/dronecan/ark_flow.md @@ -72,7 +72,6 @@ The Ark Flow will not boot if there is no SD card in the flight controller when ### Enable DroneCAN - The steps are: - In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)) and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)). @@ -111,10 +110,10 @@ When optical flow is the only source of horizontal position/velocity, then lower On the ARK Flow, you may need to configure the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings diff --git a/docs/en/dronecan/ark_flow_mr.md b/docs/en/dronecan/ark_flow_mr.md index dae831b467d0..f6207cae7310 100644 --- a/docs/en/dronecan/ark_flow_mr.md +++ b/docs/en/dronecan/ark_flow_mr.md @@ -1,6 +1,6 @@ # ARK Flow MR -ARK Flow MR ("Mid Range") is an open source [DroneCAN](index.md) [optical flow](../sensor/optical_flow.md), [distance sensor](../sensor/rangefinders.md), and IMU module. +ARK Flow MR ("Mid Range") is an open source [DroneCAN](index.md) [optical flow](../sensor/optical_flow.md), [distance sensor](../sensor/rangefinders.md), and IMU module. It is the next generation of the [Ark Flow](ark_flow.md), designed for mid-range applications. ![ARK Flow MR](../../assets/hardware/sensors/optical_flow/ark_flow_mr.jpg) @@ -28,7 +28,7 @@ Order this module from: - Invensense IIM-42653 6-Axis IMU - Two Pixhawk Standard CAN Connectors (4 Pin JST GH) - Pixhawk Standard Debug Connector (6 Pin JST SH) -- Software controlled built-in CAN termination resistor via node parameter (CANNODE_TERM) +- Software controlled built-in CAN termination resistor via node parameter (CANNODE_TERM) - Small Form Factor - 3cm x 3cm x 1.4cm - LED Indicators @@ -70,7 +70,6 @@ The Ark Flow MR will not boot if there is no SD card in the flight controller wh ### Enable DroneCAN - The steps are: - In _QGroundControl_ set the parameter [UAVCAN_ENABLE](../advanced_config/parameter_reference.md#UAVCAN_ENABLE) to `2` for dynamic node allocation (or `3` if using [DroneCAN ESCs](../dronecan/escs.md)) and reboot (see [Finding/Updating Parameters](../advanced_config/parameters.md)). @@ -106,17 +105,16 @@ Set the following parameters in _QGroundControl_: You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK Flow MR itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. | ## LED Meanings - Blinking green is normal operation - Rapid blinking blue and red is firmware update - If you see a solid red LED there is an error and you should check the following: - Make sure the flight controller has an SD card installed. diff --git a/docs/en/dronecan/ark_gps.md b/docs/en/dronecan/ark_gps.md index 51f07f92c14e..9b91601ca6eb 100644 --- a/docs/en/dronecan/ark_gps.md +++ b/docs/en/dronecan/ark_gps.md @@ -97,10 +97,10 @@ If the sensor is not centred within the vehicle you will also need to define sen You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK GPS itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ## LED Meanings diff --git a/docs/en/dronecan/ark_rtk_gps.md b/docs/en/dronecan/ark_rtk_gps.md index bbb8940fec69..e3114685fa88 100644 --- a/docs/en/dronecan/ark_rtk_gps.md +++ b/docs/en/dronecan/ark_rtk_gps.md @@ -91,10 +91,10 @@ You need to set necessary [DroneCAN](index.md) parameters and define offsets if You may need to [configure the following parameters](../dronecan/index.md#qgc-cannode-parameter-configuration) on the ARK RTK GPS itself: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------- | -| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | -| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | +| Parameter | Description | +| -------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------- | +| [CANNODE_NODE_ID](../advanced_config/parameter_reference.md#CANNODE_NODE_ID) | CAN node ID (0 for dynamic allocation). If set to 0 (default), dynamic node allocation is used. Set to 1-127 to use a static node ID. | +| [CANNODE_TERM](../advanced_config/parameter_reference.md#CANNODE_TERM) | CAN built-in bus termination. Set to `1` if this is the last node on the CAN bus. | ### Setting Up Rover and Fixed Base diff --git a/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md b/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md index 12879ef26589..de1de3651078 100644 --- a/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md +++ b/docs/en/dronecan/holybro_h_rtk_zed_f9p_gps.md @@ -100,7 +100,6 @@ In order to use dual ZED-F9P GPS heading in PX4, follow these steps: 1. Components should be visible on the left panel. Click on the first `_Component_` that maps to the ZED-F9P DroneCAN node (below shown as _Component 124_). 1. Click on the _GPS_ subsection and configure the parameters listed below: - - `GPS_TYPE`: Either set to `17` for moving baseline _base_, or set to `18` to be the moving baseline _rover_. One F9P MUST be _rover_, and the other MUST be _base_. - `GPS_AUTO_CONFIG`: set to 1 for both the rover and base diff --git a/docs/en/esc/ark_4in1_esc.md b/docs/en/esc/ark_4in1_esc.md index 5d094198ce49..40fb8d607fe5 100644 --- a/docs/en/esc/ark_4in1_esc.md +++ b/docs/en/esc/ark_4in1_esc.md @@ -32,12 +32,10 @@ Order this module from: - 10 Pin JST-SH Debug - Motor & Battery Connectors (with-connector version) - - MR30 Connector Limit Per Motor: 30A Continuous, 40A Burst - Four MR30 Motor Connectors - Dimensions (with connectors) - - Size: 77.00mm x 42.00mm x 9.43mm - Mounting Pattern: 30.5mm - Weight: 24g diff --git a/docs/en/flight_controller/airlink.md b/docs/en/flight_controller/airlink.md index 0d4fb1ec2bba..30218fc14c76 100644 --- a/docs/en/flight_controller/airlink.md +++ b/docs/en/flight_controller/airlink.md @@ -26,7 +26,6 @@ AIRLink has two computers and integrated LTE Module: ## Specifications - **Sensors** - - 3x Accelerometers, 3x Gyroscopes, 3x Magnetometers, 3x Pressure sensorss - GNSS, Rangefinders, Lidars, Optical Flow, Cameras - 3x-redundant IMU @@ -34,7 +33,6 @@ AIRLink has two computers and integrated LTE Module: - Temperature stabilization - **Flight Controller** - - STM32F7, ARM Cortex M7 with FPU, 216 MHz, 2MB Flash, 512 kB RAM - STM32F1, I/O co-processor - Ethernet, 10/100 Mbps @@ -51,7 +49,6 @@ AIRLink has two computers and integrated LTE Module: - Safety switch / LED option - **AI Mission Computer** - - 6-Core CPU: Dual-Core Cortex-A72 + Quad-Core Cortex-A53 - GPU Mali-T864, OpenGL ES1.1/2.0/3.0/3.1 - VPU with 4K VP8/9, 4K 10bits H265/H264 60fps Decoding @@ -65,7 +62,6 @@ AIRLink has two computers and integrated LTE Module: - 2x Video: 4-Lane MIPI CSI (FPV Camera) and 4-Lane MIPI CSI with HMDI Input (Payload Camera) - **LTE/5G Connectivity Module** - - Up to 600 Mbps bandwidth - 5G sub-6 and mmWave, SA and NSA operations - 4G Cat 20, up to 7xCA, 256-QAM DL/UL, 2xCA UL @@ -142,7 +138,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Left side](../../assets/flight_controller/airlink/airlink-interfaces-left.jpg) - **Left side interfaces:** - - Power input with voltage & current monitoring - AI Mission Computer micro SD card - Flight Controller micro SD card @@ -169,12 +164,12 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production - **RC Connector - JST GH SM06B-GHS-TB** | Pin number | Pin name | Direction | Voltage | Function | - | ---------- | -------- | --------- | ------- | ----------- | + | ---------- | -------- | --------- | ------- | ----------- | --- | --- | ------ | | 1 | 5V | OUT | +5V | 5V output | | 2 | PPM_IN | IN | +3.3V | PPM input | | 3 | RSSI_IN | IN | +3.3V | RSSI input | | 4 | FAN_OUT | OUT | +5V | Fan output | - | 5 | SBUS_OUT | OUT | +3.3V | SBUS output | 6 | GND | Ground | + | 5 | SBUS_OUT | OUT | +3.3V | SBUS output | 6 | GND | Ground | * **FMU SD card - microSD** @@ -183,7 +178,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Right side](../../assets/flight_controller/airlink/airlink-interfaces-right.jpg) - **Right side interfaces:** - - Ethernet port with power output - Telemetry port - Second GPS port @@ -247,7 +241,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Front side](../../assets/flight_controller/airlink/airlink-interfaces-front.jpg) - **Front side interfaces:** - - Main GNSS and compass port - Main telemetry port - CSI camera input @@ -305,7 +298,6 @@ SmartAP AIRLink's Core edition is intended for medium to high volume production ![Back side](../../assets/flight_controller/airlink/airlink-interfaces-back.jpg) - **Rear side interfaces:** - - SBUS input - 16 PWM output channels - 2x LTE antenna sockets (MIMO) diff --git a/docs/en/flight_controller/cuav_x25-evo.md b/docs/en/flight_controller/cuav_x25-evo.md index 2d53c32fbd2f..881290e9c8d6 100644 --- a/docs/en/flight_controller/cuav_x25-evo.md +++ b/docs/en/flight_controller/cuav_x25-evo.md @@ -83,7 +83,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop ### Mechanical Data - - Not provided. +- Not provided. ## Purchase Channels @@ -91,11 +91,11 @@ Order from [CUAV](https://store.cuav.net/). ## Assembly/Setup - - Not provided. +- Not provided. ## Pin Definitions - - Not provided. +- Not provided. ## Serial Port Mapping @@ -112,11 +112,13 @@ Order from [CUAV](https://store.cuav.net/). ## Voltage Ratings The _X25-EVO_ achieves triple redundancy on power supplies if three power sources are provided. The three power rails are POWERC1, POWERC2, and USB. + - **POWER C1** and **POWER C2** are DroneCAN/UAVCAN battery interfaces. **Normal Operation Maximum Ratings** Under these conditions, all power sources will be used to power the system in the following order: + 1. **POWER C1** and **POWER C2** Inputs (10V to 18V) 2. USB Input (4.75V to 5.25V) @@ -143,14 +145,14 @@ make cuav_x25-evo_default The [PX4 System Console](../debug/system_console.md) and [SWD Interface](../debug/swd_debug.md) operate on the **FMU Debug** port. -| Pin | Signal | Volt | -| -------- | ---------------- | ----- | -| 1 (red) | 5V+ | +5V | -| 2 (blk) | DEBUG TX (OUT) | +3.3V | -| 3 (blk) | DEBUG RX (IN) | +3.3V | -| 4 (blk) | FMU_SWDIO | +3.3V | -| 5 (blk) | FMU_SWCLK | +3.3V | -| 6 (blk) | GND | GND | +| Pin | Signal | Volt | +| ------- | -------------- | ----- | +| 1 (red) | 5V+ | +5V | +| 2 (blk) | DEBUG TX (OUT) | +3.3V | +| 3 (blk) | DEBUG RX (IN) | +3.3V | +| 4 (blk) | FMU_SWDIO | +3.3V | +| 5 (blk) | FMU_SWCLK | +3.3V | +| 6 (blk) | GND | GND | ## Supported Platforms / Airframes diff --git a/docs/en/flight_controller/kakuteh7-wing.md b/docs/en/flight_controller/kakuteh7-wing.md index 775eca078b59..2546a5cc01f9 100644 --- a/docs/en/flight_controller/kakuteh7-wing.md +++ b/docs/en/flight_controller/kakuteh7-wing.md @@ -1,4 +1,4 @@ -# Holybro Kakute H743-Wing +# Holybro Kakute H743-Wing @@ -9,7 +9,6 @@ Contact the [manufacturer](https://holybro.com/) for hardware support or complia The [Holybro Kakute H743 Wing](https://holybro.com/products/kakute-h743-wing) is a fully featured flight controller specifically aimed at fixed-wing and VTOL applications. It has the STM32 H743 Processor running at 480 MHz and CAN Bus support, along with dual camera support & switch, ON/OFF Pit Switch, 5V, 6V/8V, 9V/12 BEC, and plug-and-play GPS, CAN, I2C ports. - ::: info This flight controller is [manufacturer supported](../flight_controller/autopilot_manufacturer_supported.md). ::: @@ -20,7 +19,6 @@ The board can be bought from one of the following shops (for example): - [Holybro](https://holybro.com/products/kakute-h743-wing) - ## Connectors and Pins | Pin | Function | PX4 default | @@ -69,15 +67,15 @@ Firmware can be manually installed in any of the normal ways: ## Serial Port Mapping -| UART | Device | Port | Default function | -| ------ | ---------- | --------------------- | ---------------- | -| USART1 | /dev/ttyS0 | GPS 1 | GPS1 | -| USART2 | /dev/ttyS1 | R2, T2 | GPS2 | -| USART3 | /dev/ttyS2 | R3, T3 | TELEM1 | -| UART5 | /dev/ttyS3 | R5, T5 | TELEM2 | -| USART6 | /dev/ttyS4 | R6, (T6) | RC input | -| UART7 | /dev/ttyS5 | R7, T7, RTS, CTS | TELEM3 | -| UART8 | /dev/ttyS6 | R8, T8 | Console | +| UART | Device | Port | Default function | +| ------ | ---------- | ---------------- | ---------------- | +| USART1 | /dev/ttyS0 | GPS 1 | GPS1 | +| USART2 | /dev/ttyS1 | R2, T2 | GPS2 | +| USART3 | /dev/ttyS2 | R3, T3 | TELEM1 | +| UART5 | /dev/ttyS3 | R5, T5 | TELEM2 | +| USART6 | /dev/ttyS4 | R6, (T6) | RC input | +| UART7 | /dev/ttyS5 | R7, T7, RTS, CTS | TELEM3 | +| UART8 | /dev/ttyS6 | R8, T8 | Console | ## Debug Port diff --git a/docs/en/flight_controller/pixhawk_series.md b/docs/en/flight_controller/pixhawk_series.md index cc92192d483c..cf1fd037d397 100644 --- a/docs/en/flight_controller/pixhawk_series.md +++ b/docs/en/flight_controller/pixhawk_series.md @@ -102,21 +102,21 @@ At very high level, the main differences are: ### FMUv6 Comparison -| Feature | **FMUv6X-RT** | **FMUv6X** | **FMUv6C** | -| ------------------ | --------------------- | ----------------- | ------------------ | -| **FMU MCU** | NXP i.MX RT1176 | STM32H753 | STM32H743V | -| **RAM** | 2 MB | 1 MB | 1 MB | -| **Flash** | 64 MB Octal SPI | 2 MB internal | 2 MB internal | -| **IO MCU** | STM32F103 | STM32F103 | STM32F103 | -| **Secure Element** | NXP SE051 | NXP SE051 | Not supported | -| **PAB Standard** | Supported | Supported | Not supported | -| **Ethernet** | Supported | Supported | Not supported | -| **IMUs** | 3× | 3× | 2× | -| **Barometers** | 2× | 2× | 1× | -| **Magnetometer** | 1× | 1× | 1× | -| **FMU PWM** | 12× | 8× | 8× | -| **IO PWM** | 8× | 8× | 8× | -| **CAN Bus** | 3× | 2× | 2× | +| Feature | **FMUv6X-RT** | **FMUv6X** | **FMUv6C** | +| ------------------ | --------------- | ------------- | ------------- | +| **FMU MCU** | NXP i.MX RT1176 | STM32H753 | STM32H743V | +| **RAM** | 2 MB | 1 MB | 1 MB | +| **Flash** | 64 MB Octal SPI | 2 MB internal | 2 MB internal | +| **IO MCU** | STM32F103 | STM32F103 | STM32F103 | +| **Secure Element** | NXP SE051 | NXP SE051 | Not supported | +| **PAB Standard** | Supported | Supported | Not supported | +| **Ethernet** | Supported | Supported | Not supported | +| **IMUs** | 3× | 3× | 2× | +| **Barometers** | 2× | 2× | 1× | +| **Magnetometer** | 1× | 1× | 1× | +| **FMU PWM** | 12× | 8× | 8× | +| **IO PWM** | 8× | 8× | 8× | +| **CAN Bus** | 3× | 2× | 2× | ### Licensing and Trademarks diff --git a/docs/en/flight_controller/svehicle_e2.md b/docs/en/flight_controller/svehicle_e2.md index bbddcba59e80..61629c8b6a96 100644 --- a/docs/en/flight_controller/svehicle_e2.md +++ b/docs/en/flight_controller/svehicle_e2.md @@ -63,6 +63,7 @@ These flight controllers are [manufacturer supported](../flight_controller/autop Order from [S-Vehicle](https://svehicle.cn/). ## Radio Control + A Radio Control (RC) system is required if you want to manually control your vehicle (PX4 does not require a radio system for autonomous flight modes). You will need to select a compatible transmitter/receiver and then bind them so that they communicate (read the instructions that come with your specific transmitter/receiver). diff --git a/docs/en/flight_modes_fw/index.md b/docs/en/flight_modes_fw/index.md index 052bfe7dd3bd..74a7fe66f001 100644 --- a/docs/en/flight_modes_fw/index.md +++ b/docs/en/flight_modes_fw/index.md @@ -18,7 +18,7 @@ Manual-Easy: - [Altitude](../flight_modes_fw/altitude.md) — Easiest and safest _non-GPS_ manual mode. The only difference compared to _Position mode_ is that the pilot always directly controls the roll angle of the plane and there is no automatic course holding. - Altitude Cruise mode — It behaves exactly like _Altitude mode_, with the only difference being that the manual control failsafe can be disabled. This is done by setting the corresponding flag in [COM_RCL_EXCEPT](../advanced_config/parameter_reference.md#COM_RCL_EXCEPT). In that case the current altitude, airspeed and heading (by leveling out the roll angle) are kept until the manual control link is regained or the mode is exited. -It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). + It is highly recommended to only disable the manual control loss failsafe for this mode if there is a stable data link connection to the vehicle at all times, or to enable the data link loss failsafe through [NAV_DLL_ACT](../advanced_config/parameter_reference.md#NAV_DLL_ACT). - [Stabilized mode](../flight_modes_fw/stabilized.md) — The pilot directly commands the roll and pitch angle and the vehicle keeps the setpoint until the sticks are moved again. Thrust is directly set by the pilot. Turn coordination is still handled by the controller. @@ -35,6 +35,7 @@ Manual-Acrobatic Autonomous: All autonomous flight modes require a valid position estimate (GPS). Airspeed is actively controlled if an airspeed sensor is installed in any autonomous flight mode. + - [Hold](../flight_modes_fw/hold.md) — Vehicle circles around the GPS hold position at the current altitude. The mode can be used to pause a mission or to help regain control of a vehicle in an emergency. It can be activated with a pre-programmed RC switch or the QGroundControl Pause button. diff --git a/docs/en/flight_modes_fw/land.md b/docs/en/flight_modes_fw/land.md index 43d8ff92942c..77a26d0666c7 100644 --- a/docs/en/flight_modes_fw/land.md +++ b/docs/en/flight_modes_fw/land.md @@ -24,6 +24,7 @@ Where possible, instead use [Return mode](../flight_modes_fw/return.md) with a p - The mode can be triggered using the [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND) MAVLink command, or by explicitly switching to Land mode. + ::: ## Technical Summary @@ -40,12 +41,12 @@ The vehicle will flare if configured to do so (see [Flaring](../flight_modes_fw/ Land mode behaviour can be configured using the parameters below. -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------- | ---------------------------------------------------------------------------- | -| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | -| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | -| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | -| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------ | +| [NAV_LOITER_RAD](../advanced_config/parameter_reference.md#NAV_LOITER_RAD) | The loiter radius that the controller tracks for the whole landing sequence. | +| [FW_LND_ANG](../advanced_config/parameter_reference.md#FW_LND_ANG) | The flight path angle setpoint. | +| [FW_LND_AIRSPD](../advanced_config/parameter_reference.md#FW_LND_AIRSPD) | The airspeed setpoint. | +| [FW_AIRSPD_FLP_SC](../advanced_config/parameter_reference.md#FW_AIRSPD_FLP_SC) | Factor applied to the minimum airspeed when flaps are fully deployed. Necessary if FW_LND_AIRSPD is below FW_AIRSPD_MIN. | ## See Also diff --git a/docs/en/flight_modes_fw/mission.md b/docs/en/flight_modes_fw/mission.md index 91f48a83003b..f3ee6ee95f0a 100644 --- a/docs/en/flight_modes_fw/mission.md +++ b/docs/en/flight_modes_fw/mission.md @@ -28,7 +28,6 @@ Missions are uploaded onto a SD card that needs to be inserted **before** bootin At high level all vehicle types behave in the same way when MISSION mode is engaged: 1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the [mission is not feasible](#mission-feasibility-checks): - - If flying the vehicle will loiter. - If landed the vehicle will "wait". @@ -163,9 +162,9 @@ Mission Items: - [MAV_CMD_DO_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_ZOOM) - [MAV_CMD_DO_SET_CAMERA_FOCUS](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAMERA_FOCUS) - [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) - - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. - - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). - Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0). + Instead, the axis bitmask defined by [`FW_AT_AXES`](../advanced_config/parameter_reference.md#FW_AT_AXES) is used. GeoFence Definitions diff --git a/docs/en/flight_modes_mc/altitude.md b/docs/en/flight_modes_mc/altitude.md index 7d3559044393..b08688caa0d2 100644 --- a/docs/en/flight_modes_mc/altitude.md +++ b/docs/en/flight_modes_mc/altitude.md @@ -43,8 +43,8 @@ The horizontal position of the vehicle can move due to wind (or pre-existing mom The mode is affected by the following parameters: -| Parameter | Description | -| ----------------------------------------------------------------------------------------------------------- | --------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | -| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | -| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | +| Parameter | Description | +| ----------------------------------------------------------------------------------------------------------- | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | +| [MPC_Z_VEL_MAX_UP](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_UP) | Maximum vertical ascent velocity. Default: 3 m/s. | +| [MPC_Z_VEL_MAX_DN](../advanced_config/parameter_reference.md#MPC_Z_VEL_MAX_DN) | Maximum vertical descent velocity. Default: 1 m/s. | +| `MPC_XXXX` | Most of the MPC_xxx parameters affect flight behaviour in this mode (at least to some extent). For example, [MPC_THR_HOVER](../advanced_config/parameter_reference.md#MPC_THR_HOVER) defines the thrust at which a vehicle will hover. | diff --git a/docs/en/flight_modes_mc/follow_me.md b/docs/en/flight_modes_mc/follow_me.md index 08ff63687d60..33b02a896e4a 100644 --- a/docs/en/flight_modes_mc/follow_me.md +++ b/docs/en/flight_modes_mc/follow_me.md @@ -115,7 +115,6 @@ The altitude control mode determine whether the vehicle altitude is relative to The relative distance to the drone to the target will change as you ascend and descend (use with care in hilly terrain). - `2D + Terrain` makes the drone follow at a fixed height relative to the terrain underneath it, using information from a distance sensor. - - If the vehicle does not have a distance sensor following will be identical to `2D tracking`. - Distance sensors aren't always accurate and vehicles may be "jumpy" when flying in this mode. - Note that that height is relative to the ground underneath the vehicle, not the follow target. @@ -163,7 +162,6 @@ The follow-me behavior can be configured using the following parameters: - This video demonstrates a Google-Earth view perspective, by adjusting the height to around 50 meters (high), distance to 1 meter (close). Which allows a perspective as shot from a satellite. ## Known Issues diff --git a/docs/en/flight_modes_mc/mission.md b/docs/en/flight_modes_mc/mission.md index 61e235892974..04e7ccf4333f 100644 --- a/docs/en/flight_modes_mc/mission.md +++ b/docs/en/flight_modes_mc/mission.md @@ -30,7 +30,6 @@ Missions are uploaded onto a SD card that needs to be inserted **before** bootin At high level all vehicle types behave in the same way when MISSION mode is engaged: 1. If no mission is stored, or if PX4 has finished executing all mission commands, or if the [mission is not feasible](#mission-feasibility-checks): - - If flying the vehicle will hold. - If landed the vehicle will "wait". @@ -167,8 +166,8 @@ Mission Items: - `MAV_CMD_NAV_VTOL_TAKEOFF.param2` (transition heading) is ignored. Instead the heading to the next waypoint is used for the transition heading. - [MAV_CMD_DO_AUTOTUNE_ENABLE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_AUTOTUNE_ENABLE) - - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. - - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . + - Disabling autotune by setting `param1` to zero is currently not supported. To abort autotune during a mission, switch to another flight mode. + - Axis selection specified in the MAVLink message is ignored (`param2` must be set to 0) . GeoFence Definitions diff --git a/docs/en/flight_modes_vtol/return.md b/docs/en/flight_modes_vtol/return.md index cfcccf68ae68..46ec8ec1e41d 100644 --- a/docs/en/flight_modes_vtol/return.md +++ b/docs/en/flight_modes_vtol/return.md @@ -47,7 +47,6 @@ If returning as a fixed-wing, the vehicle: A mission landing pattern for a VTOL vehicle consists of a [MAV_CMD_DO_LAND_START](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_LAND_START), one or more position waypoints, and a [MAV_CMD_NAV_VTOL_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_VTOL_LAND). - If the destination is a rally point or home it will: - - Loiter/spiral down to [RTL_DESCEND_ALT](#RTL_DESCEND_ALT). - Circle for a short time, as defined by [RTL_LAND_DELAY](#RTL_LAND_DELAY). - Yaw towards the destination (centre of loiter). diff --git a/docs/en/flight_stack/controller_diagrams.md b/docs/en/flight_stack/controller_diagrams.md index b5465d50723a..26453c1361c7 100644 --- a/docs/en/flight_stack/controller_diagrams.md +++ b/docs/en/flight_stack/controller_diagrams.md @@ -13,24 +13,24 @@ The diagrams use the standard [PX4 notation](../contribute/notation.md) (and eac ![MC Controller Diagram](../../assets/diagrams/mc_control_arch.jpg) -* This is a standard cascaded control architecture. -* The controllers are a mix of P and PID controllers. -* Estimates come from [EKF2](../advanced_config/tuning_the_ecl_ekf.md). -* Depending on the mode, the outer (position) loop is bypassed (shown as a multiplexer after the outer loop). +- This is a standard cascaded control architecture. +- The controllers are a mix of P and PID controllers. +- Estimates come from [EKF2](../advanced_config/tuning_the_ecl_ekf.md). +- Depending on the mode, the outer (position) loop is bypassed (shown as a multiplexer after the outer loop). The position loop is only used when holding position or when the requested velocity in an axis is null. ### Multicopter Angular Rate Controller ![MC Rate Control Diagram](../../assets/diagrams/mc_angular_rate_diagram.jpg) -* K-PID controller. See [Rate Controller](../config_mc/pid_tuning_guide_multicopter.md#rate-controller) for more information. -* The integral authority is limited to prevent wind up. -* The outputs are limited (in the control allocation module), usually at -1 and 1. -* A Low Pass Filter (LPF) is used on the derivative path to reduce noise (the gyro driver provides a filtered derivative to the controller). +- K-PID controller. See [Rate Controller](../config_mc/pid_tuning_guide_multicopter.md#rate-controller) for more information. +- The integral authority is limited to prevent wind up. +- The outputs are limited (in the control allocation module), usually at -1 and 1. +- A Low Pass Filter (LPF) is used on the derivative path to reduce noise (the gyro driver provides a filtered derivative to the controller). ::: info The IMU pipeline is: - gyro data > apply calibration parameters > remove estimated bias > notch filter (`IMU_GYRO_NF0_BW` and `IMU_GYRO_NF0_FRQ`) > low-pass filter (`IMU_GYRO_CUTOFF`) > vehicle_angular_velocity (*filtered angular rate used by the P and I controllers*) > derivative -> low-pass filter (`IMU_DGYRO_CUTOFF`) > vehicle_angular_acceleration (*filtered angular acceleration used by the D controller*) + gyro data > apply calibration parameters > remove estimated bias > notch filter (`IMU_GYRO_NF0_BW` and `IMU_GYRO_NF0_FRQ`) > low-pass filter (`IMU_GYRO_CUTOFF`) > vehicle_angular_velocity (_filtered angular rate used by the P and I controllers_) > derivative -> low-pass filter (`IMU_DGYRO_CUTOFF`) > vehicle_angular_acceleration (_filtered angular acceleration used by the D controller_) ![IMU pipeline](../../assets/diagrams/px4_imu_pipeline.png) ::: @@ -41,51 +41,51 @@ The diagrams use the standard [PX4 notation](../contribute/notation.md) (and eac ![MC Angle Control Diagram](../../assets/diagrams/mc_angle_diagram.jpg) -* The attitude controller makes use of [quaternions](https://en.wikipedia.org/wiki/Quaternion). -* The controller is implemented from this [article](https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf). -* When tuning this controller, the only parameter of concern is the P gain. -* The rate command is saturated. +- The attitude controller makes use of [quaternions](https://en.wikipedia.org/wiki/Quaternion). +- The controller is implemented from this [article](https://www.research-collection.ethz.ch/bitstream/handle/20.500.11850/154099/eth-7387-01.pdf). +- When tuning this controller, the only parameter of concern is the P gain. +- The rate command is saturated. ### Multicopter Acceleration to Thrust and Attitude Setpoint Conversion -* The acceleration setpoints generated by the velocity controller will be converted to thrust and attitude setpoints. -* Converted acceleration setpoints will be saturated and prioritized in vertical and horizontal thrust. -* Thrust saturation is done after computing the corresponding thrust: - 1. Compute required vertical thrust (`thrust_z`) - 1. Saturate `thrust_z` with `MPC_THR_MAX` - 1. Saturate `thrust_xy` with `(MPC_THR_MAX^2 - thrust_z^2)^0.5` - -Implementation details can be found in `PositionControl.cpp` and `ControlMath.cpp`. +- The acceleration setpoints generated by the velocity controller will be converted to thrust and attitude setpoints. +- Converted acceleration setpoints will be saturated and prioritized in vertical and horizontal thrust. +- Thrust saturation is done after computing the corresponding thrust: + 1. Compute required vertical thrust (`thrust_z`) + 1. Saturate `thrust_z` with `MPC_THR_MAX` + 1. Saturate `thrust_xy` with `(MPC_THR_MAX^2 - thrust_z^2)^0.5` + +Implementation details can be found in `PositionControl.cpp` and `ControlMath.cpp`. ### Multicopter Velocity Controller ![MC Velocity Control Diagram](../../assets/diagrams/mc_velocity_diagram.png) -* PID controller to stabilise velocity. Commands an acceleration. -* The integrator includes an anti-reset windup (ARW) using a clamping method. -* The commanded acceleration is NOT saturated - a saturation will be applied to the converted thrust setpoints in combination with the maximum tilt angle. -* Horizontal gains set via parameter `MPC_XY_VEL_P_ACC`, `MPC_XY_VEL_I_ACC` and `MPC_XY_VEL_D_ACC`. -* Vertical gains set via parameter `MPC_Z_VEL_P_ACC`, `MPC_Z_VEL_I_ACC` and `MPC_Z_VEL_D_ACC`. +- PID controller to stabilise velocity. Commands an acceleration. +- The integrator includes an anti-reset windup (ARW) using a clamping method. +- The commanded acceleration is NOT saturated - a saturation will be applied to the converted thrust setpoints in combination with the maximum tilt angle. +- Horizontal gains set via parameter `MPC_XY_VEL_P_ACC`, `MPC_XY_VEL_I_ACC` and `MPC_XY_VEL_D_ACC`. +- Vertical gains set via parameter `MPC_Z_VEL_P_ACC`, `MPC_Z_VEL_I_ACC` and `MPC_Z_VEL_D_ACC`. ### Multicopter Position Controller ![MC Position Control Diagram](../../assets/diagrams/mc_position_diagram.png) -* Simple P controller that commands a velocity. -* The commanded velocity is saturated to keep the velocity in certain limits. See parameter `MPC_XY_VEL_MAX`. This parameter sets the maximum possible horizontal velocity. This differs from the maximum **desired** speed `MPC_XY_CRUISE` (autonomous modes) and `MPC_VEL_MANUAL` (manual position control mode). -* Horizontal P gain set via parameter `MPC_XY_P`. -* Vertical P gain set via parameter `MPC_Z_P`. - +- Simple P controller that commands a velocity. +- The commanded velocity is saturated to keep the velocity in certain limits. See parameter `MPC_XY_VEL_MAX`. This parameter sets the maximum possible horizontal velocity. This differs from the maximum **desired** speed `MPC_XY_CRUISE` (autonomous modes) and `MPC_VEL_MANUAL` (manual position control mode). +- Horizontal P gain set via parameter `MPC_XY_P`. +- Vertical P gain set via parameter `MPC_Z_P`. #### Combined Position and Velocity Controller Diagram ![MC Position Controller Diagram](../../assets/diagrams/px4_mc_position_controller_diagram.png) -* Mode dependent feedforwards (ff) - e.g. Mission mode trajectory generator (jerk-limited trajectory) computes position, velocity and acceleration setpoints. -* Acceleration setpoints (inertial frame) will be transformed (with yaw setpoint) into attitude setpoints (quaternion) and collective thrust setpoint. +- Mode dependent feedforwards (ff) - e.g. Mission mode trajectory generator (jerk-limited trajectory) computes position, velocity and acceleration setpoints. +- Acceleration setpoints (inertial frame) will be transformed (with yaw setpoint) into attitude setpoints (quaternion) and collective thrust setpoint. + ## Fixed-Wing Position Controller ### Total Energy Control System (TECS) @@ -117,7 +117,6 @@ An increase in pitch angle transfers kinetic to potential energy and a negative The control problem was therefore decoupled by transforming the initial setpoints into energy quantities which can be controlled independently. We use thrust to regulate the specific total energy of the vehicle and pitch maintain a specific balance between potential (height) and kinetic (speed) energy. - #### Total energy control loop ![Energy loop](../../assets/diagrams/TECS_throttle.png) @@ -130,7 +129,6 @@ We use thrust to regulate the specific total energy of the vehicle and pitch mai - The total energy of an aircraft is the sum of kinetic and potential energy: $$E_T = \frac{1}{2} m V_T^2 + m g h$$ @@ -178,7 +176,7 @@ The angular position of the control effectors (ailerons, elevators, rudders, ... Furthermore, since the control surfaces are more effective at high speed and less effective at low speed, the controller - tuned for cruise speed - is scaled using the airspeed measurements (if such a sensor is used). ::: info -If no airspeed sensor is used then gain scheduling for the FW attitude controller is disabled (it's open loop); no correction is/can be made in TECS using airspeed feedback. +If no airspeed sensor is used then gain scheduling for the FW attitude controller is disabled (it's open loop); no correction is/can be made in TECS using airspeed feedback. ::: The feedforward gain is used to compensate for aerodynamic damping. @@ -188,14 +186,12 @@ In order to keep a constant rate, this damping can be compensated using feedforw ### Turn coordination The roll and pitch controllers have the same structure and the longitudinal and lateral dynamics are assumed to be uncoupled enough to work independently. -The yaw controller, however, generates its yaw rate setpoint using the turn coordination constraint in order to minimize lateral acceleration, generated when the aircraft is slipping. The turn coordination algorithm is based solely on coordinated turn geometry calculation. +The yaw controller, however, generates its yaw rate setpoint using the turn coordination constraint in order to minimize lateral acceleration, generated when the aircraft is slipping. The turn coordination algorithm is based solely on coordinated turn geometry calculation. $$\dot{\Psi}_{sp} = \frac{g}{V_T} \tan{\phi_{sp}} \cos{\theta_{sp}}$$ The yaw rate controller also helps to counteract [adverse yaw effects](https://youtu.be/sNV_SDDxuWk) and to damp the [Dutch roll mode](https://en.wikipedia.org/wiki/Dutch_roll) by providing extra directional damping. - - ## VTOL Flight Controller ![VTOL Attitude Controller Diagram](../../assets/diagrams/VTOL_controller_diagram.png) @@ -212,12 +208,11 @@ The inputs into this block are called "virtual" as, depending on the current VTO For a standard and tilt-rotor VTOL, during transition the fixed-wing attitude controller produces the rate setpoints, which are then fed into the separate rate controllers, resulting in torque commands for the multicopter and fixed-wing actuators. For tailsitters, during transition the multicopter attitude controller is running. -The outputs of the VTOL attitude block are separate torque and force commands for the multicopter and fixed-wing actuators (two instances for `vehicle_torque_setpoint` and `vehicle_thrust_setpoint`). +The outputs of the VTOL attitude block are separate torque and force commands for the multicopter and fixed-wing actuators (two instances for `vehicle_torque_setpoint` and `vehicle_thrust_setpoint`). These are handled in an airframe-specific control allocation class. For more information on the tuning of the transition logic inside the VTOL block, see [VTOL Configuration](../config_vtol/index.md). - ### Airspeed Scaling The objective of this section is to explain with the help of equations why and how the output of the rate PI and feedforward (FF) controllers can be scaled with airspeed to improve the control performance. diff --git a/docs/en/flying/first_flight_guidelines.md b/docs/en/flying/first_flight_guidelines.md index 2aa3fd4bac15..7facee2cb7d0 100644 --- a/docs/en/flying/first_flight_guidelines.md +++ b/docs/en/flying/first_flight_guidelines.md @@ -1,6 +1,6 @@ # First Flight Guidelines -Learning to fly is a lot of fun! +Learning to fly is a lot of fun! These guidelines are designed to ensure that your first flight experience is enjoyable, educational, and safe. ## Know the Law @@ -10,10 +10,10 @@ Familiarise yourself with the flight regulations in your area. ## Select a Good Location -Selecting the right location for your first flight is critical. +Selecting the right location for your first flight is critical. The main things to look for are: -- Make sure the space is open. +- Make sure the space is open. There should be no high trees, hills or buildings nearby, because those will impair the GNSS reception. - Make sure no people are within 100 m (300 feet). - Make sure there is nothing that you shouldn't crash onto within 100 m - no houses, structures, cars, water, corn fields (hard to find drones in). @@ -24,12 +24,12 @@ The main things to look for are: ## Bring a Pro -Bring someone with experience for your first flight. +Bring someone with experience for your first flight. Get them to help you to run through the pre-flight checks and let them intervene if something goes wrong! ## Plan the Flight -Plan the flight before taking off. +Plan the flight before taking off. Make sure you know the whole route and where/how the vehicle will land. ## Limit the Damage diff --git a/docs/en/flying/missions.md b/docs/en/flying/missions.md index 607ca605f7c5..7817fa9a2a21 100644 --- a/docs/en/flying/missions.md +++ b/docs/en/flying/missions.md @@ -5,9 +5,7 @@ A mission is a predefined flight plan, which can be planned in QGroundControl an Missions typically include items for controlling taking off, flying a sequence of waypoints, capturing images and/or video, deploying cargo, and landing. QGroundControl allows you to plan missions using a fully manual approach, or you can use its more advanced features to plan ground area surveys, corridor surveys, or structure surveys. -This topic provides an overview of how to plan and fly missions. - - +This topic provides an overview of how to plan and fly missions. ## Planning Missions diff --git a/docs/en/flying/package_delivery_mission.md b/docs/en/flying/package_delivery_mission.md index 3ff6f8787451..9ad16c403cc6 100644 --- a/docs/en/flying/package_delivery_mission.md +++ b/docs/en/flying/package_delivery_mission.md @@ -32,7 +32,6 @@ To create a package delivery mission (with a Gripper): 1. Create a normal mission with a `Takeoff` mission item, and additional waypoints for your required flight path. 1. Add a waypoint on the map for where you'd like to release the package. - - To drop the package while flying set an appropriate altitude for the waypoint (and ensure the waypoint is at a safe location to drop the package). - If you'd like to land the vehicle to make the delivery you will need to change the `Waypoint` to a `Land` mission item. @@ -48,7 +47,6 @@ To create a package delivery mission (with a Gripper): 1. Configure the action for the gripper in the editor. ![Gripper action setting](../../assets/flying/qgc_mission_plan_gripper_action_setting.png) - - Set it to "Release" in order to release the package. - The gripper ID does not need to be set for now. diff --git a/docs/en/flying/plan_safety_points.md b/docs/en/flying/plan_safety_points.md index dfca1f40878e..311517c2c781 100644 --- a/docs/en/flying/plan_safety_points.md +++ b/docs/en/flying/plan_safety_points.md @@ -1,25 +1,26 @@ # Safety Points (Rally Points) Safety points are alternative [Return Mode](../flight_modes/return.md) destinations/landing points. -When enabled, the vehicle will choose the *closest return destination* of: home location, mission landing pattern or a *safety point*. +When enabled, the vehicle will choose the _closest return destination_ of: home location, mission landing pattern or a _safety point_. ![Safety Points](../../assets/qgc/plan/rally_point/rally_points.jpg) ## Creating/Defining Safety Points -Safety points are created in *QGroundControl* (which calls them "Rally Points"). +Safety points are created in _QGroundControl_ (which calls them "Rally Points"). At high level: + 1. Open **QGroundControl > Plan View** -1. Select the **Rally** tab/button on the *Plan Editor* (right of screen). +1. Select the **Rally** tab/button on the _Plan Editor_ (right of screen). 1. Select the **Rally Point** button on the toolbar (left of screen). 1. Click anywhere on the map to add a rally/safety point. - - The *Plan Editor* displays and lets you edit the current rally point (shown as a green **R** on the map). + - The _Plan Editor_ displays and lets you edit the current rally point (shown as a green **R** on the map). - You can select another rally point (shown as a more orange/yellow **R** on the map) to edit it instead. 1. Select the **Upload Required** button to upload the rally points (along with any [mission](../flying/missions.md) and [geofence](../flying/geofence.md)) to the vehicle. :::tip -More complete documentation can be found in the *QGroundControl User Guide*: [Plan View - Rally Points](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/plan_view/plan_rally_points.html). +More complete documentation can be found in the _QGroundControl User Guide_: [Plan View - Rally Points](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/plan_view/plan_rally_points.html). ::: ## Using Safety Points @@ -27,4 +28,5 @@ More complete documentation can be found in the *QGroundControl User Guide*: [Pl Safety points are not enabled by default (there are a number of different [Return Mode Types](../flight_modes/return.md#return_types)). To enable safety points: + 1. [Use the QGroundControl Parameter Editor](../advanced_config/parameters.md) to set parameter: [RTL_TYPE=3](../advanced_config/parameter_reference.md#RTL_TYPE). diff --git a/docs/en/flying/terrain_following_holding.md b/docs/en/flying/terrain_following_holding.md index fb4cc842f616..6ce0f46bdc36 100644 --- a/docs/en/flying/terrain_following_holding.md +++ b/docs/en/flying/terrain_following_holding.md @@ -1,27 +1,27 @@ # Terrain Following/Holding -PX4 supports [Terrain Following](#terrain_following) and [Terrain Hold](#terrain_hold) in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on *multicopters* and *VTOL vehicles in MC mode* that have a [distance sensor](../sensor/rangefinders.md). +PX4 supports [Terrain Following](#terrain_following) and [Terrain Hold](#terrain_hold) in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on _multicopters_ and _VTOL vehicles in MC mode_ that have a [distance sensor](../sensor/rangefinders.md). ::: info PX4 does not "natively" support terrain following in missions. -*QGroundControl* can be used to define missions that *approximately* follow terrain (this just sets waypoint altitudes based on height above terrain, where terrain height at waypoints is obtained from a map database). +_QGroundControl_ can be used to define missions that _approximately_ follow terrain (this just sets waypoint altitudes based on height above terrain, where terrain height at waypoints is obtained from a map database). ::: ## Terrain Following -*Terrain following* enables a vehicle to automatically maintain a relatively constant height above ground level when traveling at low altitudes. +_Terrain following_ enables a vehicle to automatically maintain a relatively constant height above ground level when traveling at low altitudes. This is useful for avoiding obstacles and for maintaining constant height when flying over varied terrain (e.g. for aerial photography). :::tip -This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on *multicopters* and *VTOL vehicles in MC mode* that have a [distance sensor](../sensor/rangefinders.md). +This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on _multicopters_ and _VTOL vehicles in MC mode_ that have a [distance sensor](../sensor/rangefinders.md). ::: -When *terrain following* is enabled, PX4 uses the output of the EKF estimator to provide the altitude estimate, and the estimated terrain altitude (calculated from distance sensor measurements using another estimator) to provide the altitude setpoint. +When _terrain following_ is enabled, PX4 uses the output of the EKF estimator to provide the altitude estimate, and the estimated terrain altitude (calculated from distance sensor measurements using another estimator) to provide the altitude setpoint. As the distance to ground changes, the altitude setpoint adjusts to keep the height above ground constant. -At higher altitudes (when the estimator reports that the distance sensor data is invalid) the vehicle switches to *altitude following*, and will typically fly at a near-constant height above mean sea level (AMSL) using an absolute height sensor for altitude data. +At higher altitudes (when the estimator reports that the distance sensor data is invalid) the vehicle switches to _altitude following_, and will typically fly at a near-constant height above mean sea level (AMSL) using an absolute height sensor for altitude data. ::: info More precisely, the vehicle will use the available selected sources of altitude data as defined in [Using PX4's Navigation Filter (EKF2) > Height](../advanced_config/tuning_the_ecl_ekf.md#height). @@ -29,24 +29,23 @@ More precisely, the vehicle will use the available selected sources of altitude Terrain following is enabled by setting [MPC_ALT_MODE](../advanced_config/parameter_reference.md#MPC_ALT_MODE) to `1`. - ## Terrain Hold -*Terrain hold* uses a distance sensor to help a vehicle to better maintain a constant height above ground in altitude control modes, when horizontally stationary at low altitude. +_Terrain hold_ uses a distance sensor to help a vehicle to better maintain a constant height above ground in altitude control modes, when horizontally stationary at low altitude. This allows a vehicle to avoid altitude changes due to barometer drift or excessive barometer interference from rotor wash. ::: info -This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on *multicopters* and *VTOL vehicles in MC mode* that have a [distance sensor](../sensor/rangefinders.md). +This feature can be enabled in [Position](../flight_modes_mc/position.md) and [Altitude modes](../flight_modes_mc/altitude.md), on _multicopters_ and _VTOL vehicles in MC mode_ that have a [distance sensor](../sensor/rangefinders.md). ::: -When moving horizontally (`speed >` [MPC_HOLD_MAX_XY](../advanced_config/parameter_reference.md#MPC_HOLD_MAX_XY)), or above the altitude where the distance sensor is providing valid data, the vehicle will switch into *altitude following*. +When moving horizontally (`speed >` [MPC_HOLD_MAX_XY](../advanced_config/parameter_reference.md#MPC_HOLD_MAX_XY)), or above the altitude where the distance sensor is providing valid data, the vehicle will switch into _altitude following_. Terrain holding is enabled by setting [MPC_ALT_MODE](../advanced_config/parameter_reference.md#MPC_ALT_MODE) to `2`. ::: info -*Terrain hold* is implemented similarly to [terrain following](#terrain_following). +_Terrain hold_ is implemented similarly to [terrain following](#terrain_following). It uses the output of the EKF estimator to provide the altitude estimate, and the estimated terrain altitude (calculated from distance sensor measurements using a separate, single state terrain estimator) to provide the altitude setpoint. If the distance to ground changes due to external forces, the altitude setpoint adjusts to keep the height above ground constant. ::: diff --git a/docs/en/frames_plane/index.md b/docs/en/frames_plane/index.md index ccbdc9547a5d..6108b190f31c 100644 --- a/docs/en/frames_plane/index.md +++ b/docs/en/frames_plane/index.md @@ -22,7 +22,6 @@ The linked sections instructions for assembling and configuring fixed-wing frame ## Videos - --- diff --git a/docs/en/frames_rover/index.md b/docs/en/frames_rover/index.md index 09492e324c6a..b3a705ed3173 100644 --- a/docs/en/frames_rover/index.md +++ b/docs/en/frames_rover/index.md @@ -9,13 +9,12 @@ Maintainer volunteers, [contribution](../contribute/index.md) of new features, n ![Rovers](../../assets/airframes/rover/rovers.png) - PX4 provides support for the three most common types of rovers: -| Rover Type | Steering | +| Rover Type | Steering | | --------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [**Ackermann**](#ackermann) | Direction is controlled by pointing wheels in the direction of travel. This kind of steering is used on most commercial vehicles, including cars, trucks etc. | -| [**Differential**](#differential) | Direction is controlled by moving the left- and right-side wheels at different speeds. | -| [**Mecanum**](#mecanum) | Direction is controlled by moving each mecanum wheel individually at different speeds and in different directions. | +| [**Ackermann**](#ackermann) | Direction is controlled by pointing wheels in the direction of travel. This kind of steering is used on most commercial vehicles, including cars, trucks etc. | +| [**Differential**](#differential) | Direction is controlled by moving the left- and right-side wheels at different speeds. | +| [**Mecanum**](#mecanum) | Direction is controlled by moving each mecanum wheel individually at different speeds and in different directions. | The supported frames can be seen in [Airframes Reference > Rover](../airframes/airframe_reference.md#rover). diff --git a/docs/en/frames_vtol/standardvtol.md b/docs/en/frames_vtol/standardvtol.md index f6fab32ad4ea..d244912c520a 100644 --- a/docs/en/frames_vtol/standardvtol.md +++ b/docs/en/frames_vtol/standardvtol.md @@ -4,9 +4,7 @@ A **Standard VTOL** is a [VTOL](../frames_vtol/index.md) that has _completely se ![Vertical Technologies: Deltaquad QuadPlane VTOL](../../assets/airframes/vtol/vertical_technologies_deltaquad/hero_small.png) -*Vertical Technologies: Deltaquad QuadPlane VTOL* - - +_Vertical Technologies: Deltaquad QuadPlane VTOL_ ## Videos diff --git a/docs/en/frames_vtol/tailsitter.md b/docs/en/frames_vtol/tailsitter.md index 7a393f37201a..cddc2bfb1ec7 100644 --- a/docs/en/frames_vtol/tailsitter.md +++ b/docs/en/frames_vtol/tailsitter.md @@ -86,7 +86,6 @@ This section contains videos that are specific to Tailsitter VTOL (videos that a - ## Gallery
diff --git a/docs/en/frames_vtol/tiltrotor.md b/docs/en/frames_vtol/tiltrotor.md index 320e23a5984c..c3ba16af08f1 100644 --- a/docs/en/frames_vtol/tiltrotor.md +++ b/docs/en/frames_vtol/tiltrotor.md @@ -4,7 +4,6 @@ A **Tiltrotor VTOL** is a [VTOL](../frames_vtol/index.md) vehicle that has rotor ![Horizon Hobby E-flite Convergence](../../assets/airframes/vtol/eflite_convergence_pixfalcon/hero.jpg) - ## Builds - [Convergence Tiltrotor](../frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md) diff --git a/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md b/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md index 4d81aa86259a..36ea66ad45e3 100644 --- a/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md +++ b/docs/en/frames_vtol/vtol_tiltrotor_eflite_convergence_pixfalcon.md @@ -4,20 +4,21 @@ The [E-Flite Convergence](https://youtu.be/HNedXQ_jhYo) can easily be converted There is not much space but it's enough for a [Pixfalcon](../flight_controller/pixfalcon.md) flight controller with GPS and telemetry. ::: info -The original Horizon Hobby *E-Flite Convergence* frame and [Pixfalcon](../flight_controller/pixfalcon.md) have been discontinued. +The original Horizon Hobby _E-Flite Convergence_ frame and [Pixfalcon](../flight_controller/pixfalcon.md) have been discontinued. Alternatives are provided in the [Purchase](#where-to-buy) section. ::: - ## Where to Buy Vehicle frame options: + - **WL Tech XK X450** - [AliExpress](https://www.aliexpress.com/item/1005001946025611.html) - **JJRC M02** - [Banggood (AU)](https://au.banggood.com/JJRC-M02-2_4G-6CH-450mm-Wingspan-EPO-Brushless-6-axis-Gyro-Aerobatic-RC-Airplane-RTF-3D-or-6G-Mode-Aircraft-p-1588201.html), [AliExpress](https://www.aliexpress.com/item/4001031497018.html) Flight controller options (): + - [Pixhawk 4 Mini](../flight_controller/pixhawk4_mini.md) - [Holybro Pixhawk Mini](../flight_controller/pixhawk_mini.md). - Any other compatible flight controller with small enough form-factor. @@ -25,6 +26,7 @@ Flight controller options (): ## Hardware Setup The vehicle needs 7 PWM signals for the motors and control surfaces: + - Motor (left/right/back) - Tilt servos (right/left) - Elevons (left/right) @@ -38,7 +40,6 @@ Note that left and right in the configuration screen and frame reference are def - ### Flight Controller The flight controller can be mounted at the same place the original autopilot was. @@ -58,14 +59,14 @@ That way the GPS can be put inside the body and is nicely stowed away without co ![Mount GPS](../../assets/airframes/vtol/eflite_convergence_pixfalcon/eflight_convergence_gps_mounting.jpg) - ## PX4 Configuration -Follow the [Standard Configuration](../config/index.md) in *QGroundControl* (radio, sensors, flight modes, etc.). +Follow the [Standard Configuration](../config/index.md) in _QGroundControl_ (radio, sensors, flight modes, etc.). The particular settings that are relevant to this vehicle are: + - [Airframe](../config/airframe.md) - - Select the airframe configuration **E-flite Convergence** under **VTOL Tiltrotor** and restart *QGroundControl*. + - Select the airframe configuration **E-flite Convergence** under **VTOL Tiltrotor** and restart _QGroundControl_. ![QGroundControl Vehicle Setting - Airframe selection E-Flight](../../assets/airframes/vtol/eflite_convergence_pixfalcon/qgc_setup_airframe.jpg) - [Flight Modes/Switches](../config/flight_mode.md) - As this is a VTOL vehicle, you must [assign an RC controller switch](../config/flight_mode.md#what-flight-modes-and-switches-should-i-set) for transitioning between multicopter and fixed-wing modes. diff --git a/docs/en/getting_started/flight_controller_selection.md b/docs/en/getting_started/flight_controller_selection.md index 92c300957d79..04a27a42f2f4 100644 --- a/docs/en/getting_started/flight_controller_selection.md +++ b/docs/en/getting_started/flight_controller_selection.md @@ -33,7 +33,6 @@ Similarly, PX4 can also run natively Raspberry Pi (this approach is not generall - [Raspberry Pi 2/3 Navio2](../flight_controller/raspberry_pi_navio2.md) - [Raspberry Pi 2/3/4 PilotPi Shield](../flight_controller/raspberry_pi_pilotpi.md) - ## Commercial UAVs that can run PX4 PX4 is available on many popular commercial drone products, including some that ship with PX4 and others that can be updated with PX4 (allowing you to add mission planning and other PX4 Flight modes to your vehicle). diff --git a/docs/en/getting_started/led_meanings.md b/docs/en/getting_started/led_meanings.md index cdc86d5cbbad..2e6e57e5e49d 100644 --- a/docs/en/getting_started/led_meanings.md +++ b/docs/en/getting_started/led_meanings.md @@ -1,7 +1,8 @@ # LED Meanings (Pixhawk Series) [Pixhawk-series flight controllers](../flight_controller/pixhawk_series.md) use LEDs to indicate the current status of the vehicle. -- The [UI LED](#ui_led) provides user-facing status information related to *readiness for flight*. + +- The [UI LED](#ui_led) provides user-facing status information related to _readiness for flight_. - The [Status LEDs](#status_led) provide status for the PX4IO and FMU SoC. They indicate power, bootloader mode and activity, and errors. @@ -9,7 +10,7 @@ ## UI LED -The RGB *UI LED* indicates the current *readiness for flight* status of the vehicle. +The RGB _UI LED_ indicates the current _readiness for flight_ status of the vehicle. This is typically a superbright I2C peripheral, which may or may not be mounted on the flight controller board (i.e. FMUv4 does not have one on board, and typically uses an LED mounted on the GPS). The image below shows the relationship between LED and vehicle status. @@ -19,47 +20,45 @@ It is possible to have a GPS lock (Green LED) and still not be able to arm the v ::: :::tip -In the event of an error (blinking red), or if the vehicle can't achieve GPS lock (change from blue to green), check for more detailed status information in *QGroundControl* including calibration status, and errors messages reported by the [Preflight Checks (Internal)](../flying/pre_flight_checks.md). +In the event of an error (blinking red), or if the vehicle can't achieve GPS lock (change from blue to green), check for more detailed status information in _QGroundControl_ including calibration status, and errors messages reported by the [Preflight Checks (Internal)](../flying/pre_flight_checks.md). Also check that the GPS module is properly attached, Pixhawk is reading your GPS properly, and that the GPS is sending a proper GPS position. ::: ![LED meanings](../../assets/flight_controller/pixhawk_led_meanings.gif) +- **[Solid Blue] Armed, No GPS Lock:** Indicates vehicle has been armed and has no position lock from a GPS unit. + When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. + As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. + Vehicle cannot perform guided missions in this mode. -* **[Solid Blue] Armed, No GPS Lock:** Indicates vehicle has been armed and has no position lock from a GPS unit. -When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. -As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. -Vehicle cannot perform guided missions in this mode. - -* **[Pulsing Blue] Disarmed, No GPS Lock:** Similar to above, but your vehicle is disarmed. -This means you will not be able to control motors, but all other subsystems are working. +- **[Pulsing Blue] Disarmed, No GPS Lock:** Similar to above, but your vehicle is disarmed. + This means you will not be able to control motors, but all other subsystems are working. -* **[Solid Green] Armed, GPS Lock:** Indicates vehicle has been armed and has a valid position lock from a GPS unit. -When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. -As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. -In this mode, vehicle can perform guided missions. +- **[Solid Green] Armed, GPS Lock:** Indicates vehicle has been armed and has a valid position lock from a GPS unit. + When vehicle is armed, PX4 will unlock control of the motors, allowing you to fly your drone. + As always, exercise caution when arming, as large propellers can be dangerous at high revolutions. + In this mode, vehicle can perform guided missions. -* **[Pulsing Green] Disarmed, GPS Lock:** Similar to above, but your vehicle is disarmed. +- **[Pulsing Green] Disarmed, GPS Lock:** Similar to above, but your vehicle is disarmed. This means you will not be able to control motors, but all other subsystems including GPS position lock are working. -* **[Solid Purple] Failsafe Mode:** This mode will activate whenever vehicle encounters an issue during flight, -such as losing manual control, a critically low battery, or an internal error. -During failsafe mode, vehicle will attempt to return to its takeoff location, or may simply descend where it currently is. - -* **[Solid Amber] Low Battery Warning:** Indicates your vehicle's battery is running dangerously low. -After a certain point, vehicle will go into failsafe mode. However, this mode should signal caution that it's time to end -this flight. +- **[Solid Purple] Failsafe Mode:** This mode will activate whenever vehicle encounters an issue during flight, + such as losing manual control, a critically low battery, or an internal error. + During failsafe mode, vehicle will attempt to return to its takeoff location, or may simply descend where it currently is. -* **[Blinking Red] Error / Setup Required:** Indicates that your autopilot needs to be configured or calibrated before flying. -Attach your autopilot to a Ground Control Station to verify what the problem is. -If you have completed the setup process and autopilot still appears as red and flashing, there may be another error. +- **[Solid Amber] Low Battery Warning:** Indicates your vehicle's battery is running dangerously low. + After a certain point, vehicle will go into failsafe mode. However, this mode should signal caution that it's time to end + this flight. +- **[Blinking Red] Error / Setup Required:** Indicates that your autopilot needs to be configured or calibrated before flying. + Attach your autopilot to a Ground Control Station to verify what the problem is. + If you have completed the setup process and autopilot still appears as red and flashing, there may be another error. ## Status LED -Three *Status LEDs* provide status for the FMU SoC, and three more provide status for the PX4IO (if present). +Three _Status LEDs_ provide status for the FMU SoC, and three more provide status for the PX4IO (if present). They indicate power, bootloader mode and activity, and errors. ![Pixhawk 4](../../assets/flight_controller/pixhawk4/pixhawk4_status_leds.jpg) @@ -67,11 +66,11 @@ They indicate power, bootloader mode and activity, and errors. From power on, the FMU and PX4IO CPUs first run the bootloader (BL) and then the application (APP). The table below shows how the Bootloader and then APP use the LEDs to indicate condition. -Color | Label | Bootloader usage | APP usage ---- | --- | --- | --- -Blue | ACT (Activity) | Flutters when the bootloader is receiving data | Indication of ARM state -Red/Amber | B/E (In Bootloader / Error) | Flutters when in the bootloader | Indication of an ERROR -Green |PWR (Power) | Not used by bootloader | Indication of ARM state +| Color | Label | Bootloader usage | APP usage | +| --------- | --------------------------- | ---------------------------------------------- | ----------------------- | +| Blue | ACT (Activity) | Flutters when the bootloader is receiving data | Indication of ARM state | +| Red/Amber | B/E (In Bootloader / Error) | Flutters when in the bootloader | Indication of an ERROR | +| Green | PWR (Power) | Not used by bootloader | Indication of ARM state | ::: info The LED labels shown above are commonly used, but might differ on some boards. @@ -79,11 +78,11 @@ The LED labels shown above are commonly used, but might differ on some boards. More detailed information for how to interpret the LEDs is given below (where "x" means "any state") -Red/Amber | Blue | Green | Meaning ---- | --- | --- | --- -10Hz | x | x | Overload CPU load > 80%, or RAM usage > 98% -OFF | x | x | Overload CPU load <= 80%, or RAM usage <= 98% -NA | OFF | 4 Hz| actuator_armed->armed && failsafe -NA | ON | 4 Hz | actuator_armed->armed && !failsafe -NA | OFF |1 Hz | !actuator_armed-> armed && actuator_armed->ready_to_arm -NA | OFF |10 Hz | !actuator_armed->armed && !actuator_armed->ready_to_arm +| Red/Amber | Blue | Green | Meaning | +| --------- | ---- | ----- | ------------------------------------------------------- | +| 10Hz | x | x | Overload CPU load > 80%, or RAM usage > 98% | +| OFF | x | x | Overload CPU load <= 80%, or RAM usage <= 98% | +| NA | OFF | 4 Hz | actuator_armed->armed && failsafe | +| NA | ON | 4 Hz | actuator_armed->armed && !failsafe | +| NA | OFF | 1 Hz | !actuator_armed-> armed && actuator_armed->ready_to_arm | +| NA | OFF | 10 Hz | !actuator_armed->armed && !actuator_armed->ready_to_arm | diff --git a/docs/en/getting_started/tunes.md b/docs/en/getting_started/tunes.md index 15bc693b5339..4615c101b179 100644 --- a/docs/en/getting_started/tunes.md +++ b/docs/en/getting_started/tunes.md @@ -9,16 +9,16 @@ The set of standard sounds are listed below. You can search for tune use using the string `TUNE_ID_name`(e.g. `TUNE_ID_PARACHUTE_RELEASE) ::: - ## Boot/Startup These tunes are played during the boot sequence. - + #### Startup Tone + - microSD card successfully mounted (during boot). @@ -26,36 +26,37 @@ These tunes are played during the boot sequence. #### Error Tune + - Hard fault has caused a system reboot. - System set to use PX4IO but no IO present. - UAVCAN is enabled but driver can't start. -- SITL/HITL enabled but *pwm_out_sim* driver can't start. +- SITL/HITL enabled but _pwm_out_sim_ driver can't start. - FMU startup failed. - #### Make File System + -- Formatting microSD card. +- Formatting microSD card. - Mounting failed (if formatting succeeds boot sequence will try to mount again). - No microSD card. - #### Format Failed + - Formatting microSD card failed (following previous attempt to mount card). - -#### Program PX4IO +#### Program PX4IO + - Starting to program PX4IO. @@ -63,6 +64,7 @@ These tunes are played during the boot sequence. #### Program PX4IO Success + - PX4IO programming succeeded. @@ -70,21 +72,23 @@ These tunes are played during the boot sequence. #### Program PX4IO Fail + - PX4IO programming failed. - PX4IO couldn't start. - AUX Mixer not found. - ## Operational These tones/tunes are emitted during normal operation. + #### Error Tune + - RC Loss @@ -92,6 +96,7 @@ These tones/tunes are emitted during normal operation. #### Notify Positive Tone + - Calibration succeeded. @@ -102,6 +107,7 @@ These tones/tunes are emitted during normal operation. #### Notify Neutral Tone + - Mission is valid and has no warnings. @@ -111,6 +117,7 @@ These tones/tunes are emitted during normal operation. #### Notify Negative Tone + - Calibration failed. @@ -123,6 +130,7 @@ These tones/tunes are emitted during normal operation. #### Arming Warning + - Vehicle is now armed. @@ -130,6 +138,7 @@ These tones/tunes are emitted during normal operation. #### Arming Failure Tune + - Arming failed @@ -137,6 +146,7 @@ These tones/tunes are emitted during normal operation. #### Battery Warning Slow + - Low battery warning ([failsafe](../config/safety.md#battery-level-failsafe)). @@ -144,27 +154,29 @@ These tones/tunes are emitted during normal operation. #### Battery Warning Fast + - Critical low battery warning ([failsafe](../config/safety.md#battery-level-failsafe)). - #### GPS Warning Slow + #### Parachute Release + - Parachute release triggered. - #### Single Beep + - Magnetometer/Compass calibration: Notify user to start rotating vehicle. @@ -172,6 +184,7 @@ These tones/tunes are emitted during normal operation. #### Home Set Tune + - Home position initialised (first time only). diff --git a/docs/en/getting_started/vehicle_status.md b/docs/en/getting_started/vehicle_status.md index 9fed271f74b5..b77083e876fa 100644 --- a/docs/en/getting_started/vehicle_status.md +++ b/docs/en/getting_started/vehicle_status.md @@ -7,6 +7,6 @@ In addition, PX4 provides more fine-grained information about readiness to fly i The LED, tune, and GCS notifications are linked below: -* [LED Meanings](../getting_started/led_meanings.md) -* [Tune/Sound Meanings](../getting_started/tunes.md) -* [QGroundControl Flight-Readiness Status](../flying/pre_flight_checks.md) +- [LED Meanings](../getting_started/led_meanings.md) +- [Tune/Sound Meanings](../getting_started/tunes.md) +- [QGroundControl Flight-Readiness Status](../flying/pre_flight_checks.md) diff --git a/docs/en/gps_compass/rtk_gps.md b/docs/en/gps_compass/rtk_gps.md index 29e2fe535855..9b12190bdcf2 100644 --- a/docs/en/gps_compass/rtk_gps.md +++ b/docs/en/gps_compass/rtk_gps.md @@ -20,45 +20,45 @@ The RTK compatible devices below that are expected to work with PX4 (it omits di The table indicates devices that also output yaw, and that can provide yaw when two on-vehicle units are used. It also highlights devices that connect via the CAN bus, and those which support PPK (Post-Processing Kinematic). -| Device | GPS | Compass | [DroneCAN] | [GPS Yaw] | PPK | -| :-------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :-----------------------: | :-: | -| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | | -| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | | -| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P] | | -| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | | -| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | | -| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | ✓ | | | -| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | | | -| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | | -| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | | -| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | ✓ | -| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | | -| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | | -| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | | -| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | ✘ | | -| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | ✘ | | -| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | | -| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | | -| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P] | | -| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | | -| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | | -| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | | -| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P] | | -| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | | -| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | | -| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | | -| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | | -| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | | -| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | | -| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | | -| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | | -| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | | -| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | | -| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | ✓ | -| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | ✓ | -| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | | -| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | | -| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | | +| Device | GPS | Compass | [DroneCAN] | [GPS Yaw] | PPK | +| :-------------------------------------------------------------------------------------------------------- | :------------------: | :------: | :--------: | :---------------------------------: | :-: | +| [ARK G5 RTK GPS](../dronecan/ark_g5_rtk_gps.md) | [mosaic-G5 P3] | IIS2MDC | ✓ | | | +| [ARK G5 RTK HEADING GPS](../dronecan/ark_g5_rtk_heading_gps.md) | [mosaic-G5 P3H] | IIS2MDC | ✓ | [Heading Capability][mosaic-G5 P3H] | | +| [ARK RTK GPS](../dronecan/ark_rtk_gps.md) | F9P | BMM150 | ✓ | [Dual F9P] | | +| [ARK RTK GPS L1 L5](../dronecan/ark_rtk_gps_l1_l2.md) | F9P | BMM150 | ✓ | | | +| [ARK MOSAIC-X5 RTK GPS](../dronecan/ark_mosaic__rtk_gps.md) | Mosaic-X5 | IIS2MDC | ✓ | [Septentrio Dual Antenna] | | +| [ARK X20 RTK GPS](../dronecan/ark_x20_rtk_gps.md) | X20P | IIS2MDC | ✓ | | | +| [CUAV C-RTK GPS](../gps_compass/rtk_gps_cuav_c-rtk.md) | M8P/M8N | ✓ | | | | +| [CUAV C-RTK2](../gps_compass/rtk_gps_cuav_c-rtk2.md) | F9P | ✓ | | [Dual F9P] | | +| [CUAV C-RTK 9Ps GPS](../gps_compass/rtk_gps_cuav_c-rtk-9ps.md) | F9P | RM3100 | | [Dual F9P] | | +| [CUAV C-RTK2 PPK/RTK GNSS](../gps_compass/rtk_gps_cuav_c-rtk.md) | F9P | RM3100 | | | ✓ | +| [CubePilot Here+ RTK GPS](../gps_compass/rtk_gps_hex_hereplus.md) | M8P | HMC5983 | | | | +| [CubePilot Here3 CAN GNSS GPS (M8N)](https://www.cubepilot.org/#/here/here3) | M8P | ICM20948 | ✓ | | | +| [Drotek SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | RM3100 | | [Dual F9P] | | +| [DATAGNSS NANO HRTK Receiver](../gps_compass/rtk_gps_datagnss_nano_hrtk.md) | [D10P] | IST8310 | | ✘ | | +| [DATAGNSS GEM1305 RTK Receiver](../gps_compass/rtk_gps_gem1305.md) | TAU951M | IST8310 | | ✘ | | +| [Femtones MINI2 Receiver](../gps_compass/rtk_gps_fem_mini2.md) | FB672, FB6A0 | ✓ | | | | +| [Freefly RTK GPS](../gps_compass/rtk_gps_freefly.md) | F9P | IST8310 | | | | +| [Holybro H-RTK ZED-F9P RTK Rover (DroneCAN variant)](../dronecan/holybro_h_rtk_zed_f9p_gps.md) | F9P | RM3100 | ✓ | [Dual F9P] | | +| [Holybro H-RTK ZED-F9P RTK Rover](https://holybro.com/collections/h-rtk-gps/products/h-rtk-zed-f9p-rover) | F9P | RM3100 | | [Dual F9P] | | +| [Holybro H-RTK F9P Ultralight](https://holybro.com/products/h-rtk-f9p-ultralight) | F9P | IST8310 | | [Dual F9P] | | +| [Holybro H-RTK F9P Helical or Base](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | [Dual F9P] | | +| [Holybro DroneCAN H-RTK F9P Helical](https://holybro.com/products/dronecan-h-rtk-f9p-helical) | F9P | BMM150 | ✓ | [Dual F9P] | | +| [Holybro H-RTK F9P Rover Lite](../gps_compass/rtk_gps_holybro_h-rtk-f9p.md) | F9P | IST8310 | | | | +| [Holybro DroneCAN H-RTK F9P Rover](https://holybro.com/products/dronecan-h-rtk-f9p-rover) | F9P | BMM150 | | [Dual F9P] | | +| [Holybro H-RTK M8P GNSS](../gps_compass/rtk_gps_holybro_h-rtk-m8p.md) | M8P | IST8310 | | | | +| [Holybro H-RTK Unicore UM982 GPS](../gps_compass/rtk_gps_holybro_unicore_um982.md) | UM982 | IST8310 | | [Unicore Dual Antenna] | | +| [LOCOSYS Hawk R1](../gps_compass/rtk_gps_locosys_r1.md) | MC-1612-V2b | | | | | +| [LOCOSYS Hawk R2](../gps_compass/rtk_gps_locosys_r2.md) | MC-1612-V2b | IST8310 | | | | +| [mRo u-blox ZED-F9 RTK L1/L2 GPS](https://store.mrobotics.io/product-p/m10020d.htm) | F9P | ✓ | | [Dual F9P] | | +| [Navisys L1/L2 ZED-F9P RTK - Base only](https://www.navisys.com.tw/productdetail?name=GR901&class=RTK) | F9P | | | | | +| [RaccoonLab L1/L2 ZED-F9P][RaccoonLab L1/L2 ZED-F9P] | F9P | RM3100 | ✓ | | | +| [RaccoonLab L1/L2 ZED-F9P with external antenna][RaccnLabL1L2ZED-F9P ext_ant] | F9P | RM3100 | ✓ | | | +| [Septentrio AsteRx-m3 Pro](../gps_compass/septentrio_asterx-rib.md) | AsteRx | ✓ | | [Septentrio Dual Antenna] | ✓ | +| [Septentrio mosaic-go](../gps_compass/septentrio_mosaic-go.md) | mosaic X5 / mosaic H | ✓ | | [Septentrio Dual Antenna] | ✓ | +| [SIRIUS RTK GNSS ROVER (F9P)](https://store-drotek.com/911-sirius-rtk-gnss-rover-f9p.html) | F9P | ✓ | | [Dual F9P] | | +| [SparkFun GPS-RTK2 Board - ZED-F9P](https://www.sparkfun.com/products/15136) | F9P | ✓ | | [Dual F9P] | | +| [Trimble MB-Two](../gps_compass/rtk_gps_trimble_mb_two.md) | F9P | ✓ | | ✓ | | @@ -150,7 +150,6 @@ The RTK GPS connection is essentially plug and play: ![survey-in](../../assets/qgc/setup/rtk/qgc_rtk_survey-in.png) 1. Once Survey-in completes: - - The RTK GPS icon changes to white and _QGroundControl_ starts to stream position data to the vehicle: ![RTK streaming](../../assets/qgc/setup/rtk/qgc_rtk_streaming.png) diff --git a/docs/en/log/flight_review.md b/docs/en/log/flight_review.md index a9e8ccd31838..49d2d5c2409f 100644 --- a/docs/en/log/flight_review.md +++ b/docs/en/log/flight_review.md @@ -36,6 +36,7 @@ For the rate controller in particular, it is useful to enable the high-rate logg Vibration is one of the most common problems for multirotor vehicles. High vibration levels can lead to: + - less efficient flight and reduced flight time - the motors can heat up - increased material wearout @@ -45,7 +46,7 @@ High vibration levels can lead to: It is therefore important to keep an eye on the vibration levels and improve the setup if needed. -There is a point where vibration levels are clearly too high, and generally lower vibration levels are better. +There is a point where vibration levels are clearly too high, and generally lower vibration levels are better. However there is a broad range between 'everything is ok' and 'the levels are too high'. This range depends on a number of factors, including vehicle size - as larger vehicles have higher inertia, allowing for more software filtering (at the same time the vibrations on larger vehicles are of lower frequency). @@ -61,7 +62,7 @@ It is worth looking at multiple charts when analyzing vibration (different chart You need to enable the high-rate logging profile ([SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE)) to see this plot. ::: -This graph shows a frequency plot for the roll, pitch and yaw axis based on the actuator controls signal (the PID output from the rate controller). +This graph shows a frequency plot for the roll, pitch and yaw axis based on the actuator controls signal (the PID output from the rate controller). It helps to identify frequency peaks and configuring the software filters. There should only be a single peak at the lowest end (below around 20 Hz), the rest should be low and flat. @@ -96,7 +97,6 @@ This example shows a peak in frequency close to 50 Hz (in this case due to "loos ![Vibrations in landing gear - FFT plot](../../assets/flight_log_analysis/flight_review/vibrations_landing_gear_actuator_controls_fft.png) - ### Acceleration Power Spectral Density This is a 2D frequency plot showing the frequency response of the raw accelerometer data over time (it displays the sum for the x, y and z axis). @@ -104,12 +104,12 @@ The more yellow an area is, the higher the frequency response at that time and f Ideally only the lowest part up to a few Hz is yellow, and the rest is mostly green or blue. - #### Examples: Good Vibration [QAV-R 5" Racer](../frames_multicopter/qav_r_5_kiss_esc_racer.md) frame (excellent vibration). ![Low vibration QAV-R 5 Racer - spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_good_spectral.png) + DJI F450 frame (good vibration). @@ -122,7 +122,6 @@ Above you can see the blade passing frequency of the propellers at around 100 Hz S500 frame: ![Vibration S500 - spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_s500_spectral.png) - #### Examples: Bad Vibration The strong yellow lines at around 100Hz indicate a potential issue that requires further investigation (starting with a review of the other charts). @@ -138,7 +137,6 @@ With the default filter settings of 80 Hz vibrations at 50 Hz will not be filter ![Vibrations in landing gear - spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_landing_gear_spectral.png) - Extremely high (unsafe) vibration! Note that the graph is almost completely yellow. :::warning @@ -147,13 +145,12 @@ You should not fly with such high vibration levels. ![Exceedingly high vibration in spectral density plot](../../assets/flight_log_analysis/flight_review/vibrations_exceedingly_high_spectral.png) - ### Raw Acceleration -This graph shows the raw accelerometer measurements for the x, y and z axis. +This graph shows the raw accelerometer measurements for the x, y and z axis. Ideally each line is thin and clearly shows the vehicle's accelerations. -As a rule of thumb if the z-axis graph is touching the x/y-axis graph during hover or slow flight, the vibration levels are too high. +As a rule of thumb if the z-axis graph is touching the x/y-axis graph during hover or slow flight, the vibration levels are too high. :::tip The best way to use this graph is to zoom in a bit to a part where the vehicle is hovering. @@ -170,7 +167,6 @@ DJI F450 frame (good vibration). - #### Examples: Bad Vibration @@ -179,18 +175,15 @@ This is at the limit where it starts to negatively affect flight performance. ![Borderline vibration S500 x, y - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_s500_accel.png) - Vibration too high. Note how the graph of the z-axis overlaps with the x/y-axis graph: ![Vibrations in landing gear - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_landing_gear_accel.png) - Vibration levels are too high. Note how the graph of the z-axis overlaps with the x/y-axis graph: ![High vibration in raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_too_high_accel.png) - -Very high (unsafe) vibration levels. +Very high (unsafe) vibration levels. :::warning You should not fly with such high vibration levels. @@ -198,7 +191,6 @@ You should not fly with such high vibration levels. ![Exceedingly high vibration in raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_exceedingly_high_accel.png) - ### Raw High-rate IMU Data Plots @@ -207,16 +199,17 @@ For an in-depth analysis there is an option to log the raw IMU data at full rate This allows inspection of much higher frequencies than with normal logging, which can help when selecting vibration mounts or configuring low-pass and notch filters appropriately. To use it, some parameters need to be changed: + - Set [IMU_GYRO_RATEMAX](../advanced_config/parameter_reference.md#IMU_GYRO_RATEMAX) to 400. - This ensures that the raw sensor data is more efficiently packed when sent from the sensor to the rest of the system, and reduces the log size (without reducing useful data). + This ensures that the raw sensor data is more efficiently packed when sent from the sensor to the rest of the system, and reduces the log size (without reducing useful data). - Use a good SD card, as the IMU data requires a high logging bandwidth (Flight Review will show dropouts if the logging rate gets too high). - + :::tip See [Logging > SD Cards](../dev_log/logging.md#sd-cards) for a comparison of popular SD card. ::: - + - Enable either the gyro or accel high-rate FIFO profile in [SDLOG_PROFILE](../advanced_config/parameter_reference.md#SDLOG_PROFILE) and disable the rest of the entries. If you are using a really good SD card (seeing few/no dropouts), you can: - either enable both accel and gyro profiles @@ -244,17 +237,16 @@ Often a source of vibration (or combination of multiple sources) cannot be ident In this case the vehicle should be inspected. [Vibration Isolation](../assembly/vibration_isolation.md) explains some basic things you can check (and do) to reduce vibration levels. - - ## Actuator Outputs -The *Actuator Outputs* graph shows the signals that are sent to the individual actuators (motors/servos). +The _Actuator Outputs_ graph shows the signals that are sent to the individual actuators (motors/servos). Generally it is in the range between the minimum and maximum configured PWM values (e.g. from 1000 to 2000). This is an example for a quadrotor where everything is OK (all of the signals are within the range, approximately overlap each other, and are not too noisy): ![Good actuator outputs](../../assets/flight_log_analysis/flight_review/actuator_outputs_good.png) The plot can help to identify different problems: + - If one or more of the signals is at the maximum over a longer time, it means the controller runs into **saturation**. It is not necessarily a problem, for example when flying at full throttle this is expected. But if it happens for example during a mission, it's an indication that the vehicle is overweight for the amount of thrust that it can provide. @@ -270,20 +262,20 @@ The plot can help to identify different problems: This is an example from a hexarotor: motors 1, 3 and 6 run at higher thrust: ![Hexrotor imbalanced actuator outputs](../../assets/flight_log_analysis/flight_review/actuator_outputs_hex_imbalanced.png) + - If the signals look very **noisy** (with high amplitudes), it can have two causes: sensor noise or vibrations passing through the controller (this shows up in other plots as well, see previous section) or too high PID gains. This is an extreme example: ![Noisy actuator outputs - extreme case](../../assets/flight_log_analysis/flight_review/actuator_outputs_noisy.png) - ## GPS Uncertainty -The *GPS Uncertainty* plot shows information from the GPS device: +The _GPS Uncertainty_ plot shows information from the GPS device: + - Number of used satellites (should be around 12 or higher) - Horizontal position accuracy (should be below 1 meter) - Vertical position accuracy (should be below 2 meters) - GPS fix: this is 3 for a 3D GPS fix, 4 for GPS + Dead Reckoning, 5 for RTK float and 6 for RTK fixed type - ## GPS Noise & Jamming The GPS Noise & Jamming plot is useful to check for GPS signal interferences and jamming. @@ -301,21 +293,21 @@ This is an example without any interference: ![GPS jamming - good plot](../../assets/flight_log_analysis/flight_review/gps_jamming_good.png) - ## Thrust and Magnetic Field -The *Thrust and Magnetic Field* plot shows the thrust and the norm of the magnetic sensor measurement vector. +The _Thrust and Magnetic Field_ plot shows the thrust and the norm of the magnetic sensor measurement vector. The norm should be constant over the whole flight and uncorrelated with the thrust. This is a good example where the norm is very close to constant: ![Thrust and mag close to constant](../../assets/flight_log_analysis/flight_review/thrust_and_mag_good.png) -*If it is correlated*, it means that the current drawn by the motors (or other consumers) is influencing the magnetic field. +_If it is correlated_, it means that the current drawn by the motors (or other consumers) is influencing the magnetic field. This must be avoided as it leads to incorrect yaw estimation. The following plot shows a strong correlation between the thrust and the norm of the magnetometer: ![Correlated thrust and mag](../../assets/flight_log_analysis/flight_review/thrust_and_mag_correlated.png) Solutions to this are: + - Use an external magnetometer (avoid using the internal magnetometer) - If using an external magnetometer, move it further away from strong currents (i.e. by using a (longer) GPS mast). @@ -325,10 +317,9 @@ However it could also be due to external disturbances (for example when flying c This example shows that the norm is non-constant, but it does not correlate with the thrust: ![Uncorrelated thrust and mag](../../assets/flight_log_analysis/flight_review/thrust_and_mag_uncorrelated_problem.png) - ## Estimator Watchdog -The *Estimator Watchdog* plot shows the health report of the estimator. +The _Estimator Watchdog_ plot shows the health report of the estimator. It should be constant zero. This is what it should look like if there are no problems: @@ -337,12 +328,12 @@ This is what it should look like if there are no problems: If one of the flags is non-zero, the estimator detected a problem that needs to be further investigated. Most of the time it is an issue with a sensor, for example magnetometer interferences. It usually helps to look at the plots of the corresponding sensor. + Here is an example with magnetometer problems: ![Estimator watchdog with magnetometer problems](../../assets/flight_log_analysis/flight_review/estimator_watchdog_mag_problem.png) - ## Sampling Regularity of Sensor Data The sampling regularity plot provides insights into problems with the logging system and scheduling. @@ -373,14 +364,13 @@ The following example contains too many dropouts, the quality of the used SD car ## Logged Messages -This is a table with system error and warning messages. +This is a table with system error and warning messages. For example they show when a task becomes low on stack size. The messages need to be examined individually, and not all of them indicate a problem. For example the following shows a kill-switch test: ![Logged Messages](../../assets/flight_log_analysis/flight_review/logged_messages.png) - ## Flight/Frame Log Review Examples It is often worth looking at multiple charts for a particular flight when analyzing vehicle condition (different charts can better highlight some issues). @@ -391,9 +381,11 @@ The section below groups a few (previously presented) charts by flight/vehicle. ### QAV-R 5" Racer These charts are all from the same flight of a [QAV-R 5" Racer](../frames_multicopter/qav_r_5_kiss_esc_racer.md). + They show a vehicle that has very low vibration: + - Actuator Controls FFT shows only a single peak at the lowest end, with the rest low and flat. - Spectral density is mostly green, with only a little yellow at the low frequencies. - Raw Acceleration has z-axis trace well separated from the x/y-axis traces. @@ -404,14 +396,15 @@ They show a vehicle that has very low vibration: ![Low vibration QAV-R 5 Racer - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_good_accel.png) - ### DJI F450 -These charts are all from the same flight of a *DJI F450*. +These charts are all from the same flight of a _DJI F450_. + They show a vehicle that has low vibration (but not as low as the QAV-R above!): -- Actuator Controls FFT shows a peak at the lowest end. + +- Actuator Controls FFT shows a peak at the lowest end. Most of the rest is flat, except for a bump at around 100Hz (this is the blade passing frequency of the propellers). - Spectral density is mostly green. The blade passing frequency is again visible. - Raw Acceleration has z-axis trace well separated from the x/y-axis traces. @@ -422,16 +415,16 @@ They show a vehicle that has low vibration (but not as low as the QAV-R above!): ![Low vibration DJI F450 - raw accel. plot](../../assets/flight_log_analysis/flight_review/vibrations_f450_accel.png) - ### S500 These charts are all from the same flight of an S500. They show a vehicle that has borderline-acceptable vibration: -- Actuator Controls FFT shows a peak at the lowest end. + +- Actuator Controls FFT shows a peak at the lowest end. Most of the rest is flat, except for a bump at around 100Hz. - Spectral density is mostly green, but more yellow than for the DJI F450 at 100Hz. -- Raw Acceleration has z-axis trace fairly close to the x/y-axis traces. +- Raw Acceleration has z-axis trace fairly close to the x/y-axis traces. This is at the limit where it starts to negatively affect flight performance. ![Low vibration S500 actuator controls - FFT plot](../../assets/flight_log_analysis/flight_review/vibrations_s500_actuator_controls_fft.png) diff --git a/docs/en/log/plotjuggler_log_analysis.md b/docs/en/log/plotjuggler_log_analysis.md index be9b0be76f43..25cd7ce6eb1c 100644 --- a/docs/en/log/plotjuggler_log_analysis.md +++ b/docs/en/log/plotjuggler_log_analysis.md @@ -66,17 +66,17 @@ This shows the position / velocity relationship described above in detail. ::: info Try out the boat testing log analysis yourself by downloading the ULog and Layout file used above! + - [Boat testing ULog](https://github.com/PX4/PX4-Autopilot/raw/main/docs/assets/flight_log_analysis/plot_juggler/sample_log_boat_testing_2022-7-28-13-31-16.ulg) - [Boat testing Analysis Layout](https://raw.githubusercontent.com/PX4/PX4-user_guide/main/assets/flight_log_analysis/plot_juggler/sample_log_boat_testing_layout.xml) -::: + ::: ### Layout Templates There are a number of PlotJuggler layout files shared by PX4 Developers. Each can be used for a specific purpose (Multicopter tuning, VTOL tuning, Boat debugging, etc.): -* [Sample View layout](https://github.com/PX4/PX4-user_guide/blob/main/assets/flight_log_analysis/plot_juggler/plotjuggler_sample_view.xml) : Template used in the [Multi-panel example](#splitting-horizontally-vertically-multi-panel) above. - +- [Sample View layout](https://github.com/PX4/PX4-user_guide/blob/main/assets/flight_log_analysis/plot_juggler/plotjuggler_sample_view.xml) : Template used in the [Multi-panel example](#splitting-horizontally-vertically-multi-panel) above. ## Advanced Usage @@ -105,6 +105,7 @@ Here the custom series `Roll` is displayed along with other timeseries, includin ![Quaternion Roll plotted](../../assets/flight_log_analysis/plot_juggler/plotjuggler_quaternion_roll_plotted.png) The `quat_to_roll` function looks like this: + ```lua w = value x = v1 diff --git a/docs/en/middleware/drivers.md b/docs/en/middleware/drivers.md index 6b29331d2190..e64a3bfefb96 100644 --- a/docs/en/middleware/drivers.md +++ b/docs/en/middleware/drivers.md @@ -1,27 +1,27 @@ # Driver Development -PX4 device drivers are based on the [Device](https://github.com/PX4/PX4-Autopilot/tree/main/src/lib/drivers/device) framework. +PX4 device drivers are based on the [Device](https://github.com/PX4/PX4-Autopilot/tree/main/src/lib/drivers/device) framework. ## Creating a Driver PX4 almost exclusively consumes data from [uORB](../middleware/uorb.md). Drivers for common peripheral types must publish the correct uORB messages (for example: gyro, accelerometer, pressure sensors, etc.). -The best approach for creating a new driver is to start with a similar driver as a template (see [src/drivers](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers)). +The best approach for creating a new driver is to start with a similar driver as a template (see [src/drivers](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers)). ::: info More detailed information about working with specific I/O buses and sensors may be available in [Sensor and Actuator Buses](../sensor_bus/index.md) section. ::: ::: info -Publishing the correct uORB topics is the only pattern that drivers *must* follow. +Publishing the correct uORB topics is the only pattern that drivers _must_ follow. ::: ## Core Architecture PX4 is a [reactive system](../concept/architecture.md) and uses [uORB](../middleware/uorb.md) publish/subscribe to transport messages. File handles are not required or used for the core operation of the system. Two main APIs are used: -* The publish / subscribe system which has a file, network or shared memory backend depending on the system PX4 runs on. -* The global device registry, which can be used to enumerate devices and get/set their configuration. This can be as simple as a linked list or map to the file system. +- The publish / subscribe system which has a file, network or shared memory backend depending on the system PX4 runs on. +- The global device registry, which can be used to enumerate devices and get/set their configuration. This can be as simple as a linked list or map to the file system. ## Device IDs @@ -33,7 +33,6 @@ The order of sensors (e.g. if there is a `/dev/mag0` and an alternate `/dev/mag1 For the example of three magnetometers on a system, use the flight log (.px4log) to dump the parameters. The three parameters encode the sensor IDs and `MAG_PRIME` identifies which magnetometer is selected as the primary sensor. Each MAGx_ID is a 24bit number and should be padded left with zeros for manual decoding. - ``` CAL_MAG0_ID = 73225.0 CAL_MAG1_ID = 66826.0 @@ -83,6 +82,7 @@ struct DeviceStructure { uint8_t devtype; // device class specific device type }; ``` + The `bus_type` is decoded according to: ```C @@ -126,17 +126,19 @@ Drivers (and other modules) output minimally verbose logs strings by default (e. Log verbosity is defined at build time using the `RELEASE_BUILD` (default), `DEBUG_BUILD` (verbose) or `TRACE_BUILD` (extremely verbose) macros. Change the logging level using `COMPILE_FLAGS` in the driver `px4_add_module` function (**CMakeLists.txt**). -The code fragment below shows the required change to enable DEBUG_BUILD level debugging for a single module or driver. +The code fragment below shows the required change to enable DEBUG_BUILD level debugging for a single module or driver. ``` px4_add_module( MODULE templates__module MAIN module ``` + ``` COMPILE_FLAGS -DDEBUG_BUILD ``` + ``` SRCS module.cpp diff --git a/docs/en/middleware/index.md b/docs/en/middleware/index.md index dc9d0464b74b..3c35eeb96c2a 100644 --- a/docs/en/middleware/index.md +++ b/docs/en/middleware/index.md @@ -1,6 +1,6 @@ # Middleware -This section contains topics about PX4 middleware, including PX4 internal communication mechanisms ([uORB](../middleware/uorb.md)), and between PX4 and offboard systems like companion computers and GCS (e.g. [MAVLink](../middleware/mavlink.md), [uXRCE-DDS](../middleware/uxrce_dds.md)). +This section contains topics about PX4 middleware, including PX4 internal communication mechanisms ([uORB](../middleware/uorb.md)), and between PX4 and offboard systems like companion computers and GCS (e.g. [MAVLink](../middleware/mavlink.md), [uXRCE-DDS](../middleware/uxrce_dds.md)). :::tip For a detailed overview of the platform architecture see the [Architectural Overview](../concept/architecture.md). diff --git a/docs/en/middleware/uorb_graph.md b/docs/en/middleware/uorb_graph.md index 7376e951b640..9dbdb57c2d94 100644 --- a/docs/en/middleware/uorb_graph.md +++ b/docs/en/middleware/uorb_graph.md @@ -10,7 +10,6 @@ Usage instructions are provided [below](#graph-properties). import { withBase } from 'vitepress'; - ## Graph Properties The graph has the following properties: @@ -27,5 +26,5 @@ The graph has the following properties: - Double-clicking on a topic opens its message definition. - Make sure your browser window is wide enough to display the full graph (the sidebar menu can be hidden with the icon in the top-left corner). You can also zoom the image. -- The *Preset* selection list allows you to refine the list of modules that are shown. -- The *Search* box can be used to find particular modules/topics (topics that are not selected by the search are greyed-out). +- The _Preset_ selection list allows you to refine the list of modules that are shown. +- The _Search_ box can be used to find particular modules/topics (topics that are not selected by the search are greyed-out). diff --git a/docs/en/modules/module_template.md b/docs/en/modules/module_template.md index 5d9fa26c6a22..291c6ff0cfdc 100644 --- a/docs/en/modules/module_template.md +++ b/docs/en/modules/module_template.md @@ -1,6 +1,6 @@ # Module Template for Full Applications -An application can be written to run as either a *task* (a module with its own stack and process priority) or as a *work queue task* (a module that runs on a work queue thread, sharing the stack and thread priority with other tasks on the work queue). +An application can be written to run as either a _task_ (a module with its own stack and process priority) or as a _work queue task_ (a module that runs on a work queue thread, sharing the stack and thread priority with other tasks on the work queue). In most cases a work queue task can be used, as this minimizes resource usage. ::: info @@ -13,26 +13,28 @@ All the things learned in the [First Application Tutorial](../modules/hello_sky. ## Work Queue Task -PX4-Autopilot contains a template for writing a new application (module) that runs as a *work queue task*: +PX4-Autopilot contains a template for writing a new application (module) that runs as a _work queue task_: [src/examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/work_item). A work queue task application is just the same as an ordinary (task) application, except that it needs to specify that it is a work queue task, and schedule itself to run during initialisation. The example shows how. In summary: + 1. Specify the dependency on the work queue library in the cmake definition file ([CMakeLists.txt](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/CMakeLists.txt)): ``` ... DEPENDS px4_work_queue ``` -1. In addition to `ModuleBase`, the task should also derive from `ScheduledWorkItem` (included from [ScheduledWorkItem.hpp]( https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp)) +1. In addition to `ModuleBase`, the task should also derive from `ScheduledWorkItem` (included from [ScheduledWorkItem.hpp](https://github.com/PX4/PX4-Autopilot/blob/main/platforms/common/include/px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp)) 1. Specify the queue to add the task to in the constructor initialisation. The [work_item](https://github.com/PX4/PX4-Autopilot/blob/main/src/examples/work_item/WorkItemExample.cpp#L42) example adds itself to the `wq_configurations::test1` work queue as shown below: + ```cpp WorkItemExample::WorkItemExample() : - ModuleParams(nullptr), - ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::test1) { } ``` @@ -45,8 +47,6 @@ In summary: 1. Implement the `task_spawn` method, specifying that the task is a work queue (using the `task_id_is_work_queue` id. 1. Schedule the work queue task using one of the scheduling methods (in the example we use `ScheduleOnInterval` from within the `init` method). - - ## Tasks PX4/PX4-Autopilot contains a template for writing a new application (module) that runs as a task on its own stack: diff --git a/docs/en/modules/modules_autotune.md b/docs/en/modules/modules_autotune.md index 2292dd749441..f0570f892598 100644 --- a/docs/en/modules/modules_autotune.md +++ b/docs/en/modules/modules_autotune.md @@ -1,15 +1,11 @@ # Modules Reference: Autotune - - ## fw_autotune_attitude_control Source: [modules/fw_autotune_attitude_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/fw_autotune_attitude_control) - ### Description - ### Usage {#fw_autotune_attitude_control_usage} ``` @@ -27,10 +23,8 @@ fw_autotune_attitude_control [arguments...] Source: [modules/mc_autotune_attitude_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_autotune_attitude_control) - ### Description - ### Usage {#mc_autotune_attitude_control_usage} ``` diff --git a/docs/en/modules/modules_command.md b/docs/en/modules/modules_command.md index 4bba93f042d5..499d7f1fdb9a 100644 --- a/docs/en/modules/modules_command.md +++ b/docs/en/modules/modules_command.md @@ -1,12 +1,9 @@ # Modules Reference: Command - - ## actuator_test Source: [systemcmds/actuator_test](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/actuator_test) - Utility to test actuators. WARNING: remove all props before using this command. @@ -36,6 +33,7 @@ actuator_test [arguments...] Source: [systemcmds/bl_update](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bl_update) Utility to flash the bootloader from a file + ### Usage {#bl_update_usage} ``` @@ -51,6 +49,7 @@ bl_update [arguments...] Source: [systemcmds/bsondump](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/bsondump) Utility to read BSON from a file and print or output document size. + ### Usage {#bsondump_usage} ``` @@ -63,6 +62,7 @@ bsondump [arguments...] Source: [systemcmds/dumpfile](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dumpfile) Dump file utility. Prints file size and contents in binary mode (don't replace LF with CR LF) to stdout. + ### Usage {#dumpfile_usage} ``` @@ -74,16 +74,16 @@ dumpfile [arguments...] Source: [systemcmds/dyn](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/dyn) - ### Description + Load and run a dynamic PX4 module, which was not compiled into the PX4 binary. ### Example + ``` dyn ./hello.px4mod start ``` - ### Usage {#dyn_usage} ``` @@ -96,14 +96,16 @@ dyn [arguments...] Source: [systemcmds/failure](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/failure) - ### Description + Inject failures into system. ### Implementation + This system command sends a vehicle command over uORB to trigger failure. ### Examples + Test the GPS failsafe by stopping GPS: failure gps off @@ -125,32 +127,37 @@ failure [arguments...] Source: [systemcmds/gpio](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/gpio) - ### Description + This command is used to read and write GPIOs + ``` gpio read / [PULLDOWN|PULLUP] [--force] gpio write / [PUSHPULL|OPENDRAIN] [--force] ``` ### Examples + Read the value on port H pin 4 configured as pullup, and it is high + ``` gpio read H4 PULLUP ``` + 1 OK Set the output value on Port E pin 7 to high + ``` gpio write E7 1 --force ``` Set the output value on device /dev/gpio1 to high + ``` gpio write /dev/gpio1 1 ``` - ### Usage {#gpio_usage} ``` @@ -203,6 +210,7 @@ hardfault_log [arguments...] Source: [systemcmds/hist](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/hist) Command-line tool to show the px4 message history. There are no arguments. + ### Usage {#hist_usage} ``` @@ -214,6 +222,7 @@ hist [arguments...] Source: [systemcmds/i2cdetect](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/i2cdetect) Utility to scan for I2C devices on a particular bus. + ### Usage {#i2cdetect_usage} ``` @@ -226,8 +235,8 @@ i2cdetect [arguments...] Source: [systemcmds/led_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/led_control) - ### Description + Command-line tool to control & test the (external) LED's. To use it make sure there's a driver running, which handles the led_control uorb topic. @@ -237,12 +246,13 @@ module can blink N times with high priority, and the LED's automatically return after the blinking. The `reset` command can also be used to return to a lower priority. ### Examples + Blink the first LED 5 times in blue: + ``` led_control blink -c blue -l 0 -n 5 ``` - ### Usage {#led_control_usage} ``` @@ -279,7 +289,6 @@ led_control [arguments...] Source: [systemcmds/topic_listener](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/topic_listener) - Utility to listen on uORB topics and print the data to the console. The listener can be exited any time by pressing Ctrl+C, Esc, or Q. @@ -303,6 +312,7 @@ listener [arguments...] Source: [systemcmds/mft](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft) Utility interact with the manifest + ### Usage {#mfd_usage} ``` @@ -316,6 +326,7 @@ mfd [arguments...] Source: [systemcmds/mft_cfg](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mft_cfg) Tool to set and get manifest configuration + ### Usage {#mft_cfg_usage} ``` @@ -336,6 +347,7 @@ mft_cfg [arguments...] Source: [systemcmds/mtd](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/mtd) Utility to mount and test partitions (based on FRAM/EEPROM storage as defined by the board) + ### Usage {#mtd_usage} ``` @@ -378,8 +390,8 @@ nshterm [arguments...] Source: [systemcmds/param](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/param) - ### Description + Command to access and manipulate parameters via shell or script. This is used for example in the startup script to set airframe-specific parameters. @@ -396,7 +408,9 @@ Each parameter has a 'used' flag, which is set when it's read during boot. It is parameters to a ground control station. ### Examples + Change the airframe and make sure the airframe's default parameters are loaded: + ``` param set SYS_AUTOSTART 4001 param set SYS_AUTOCONFIG 1 @@ -476,12 +490,11 @@ param [arguments...] Source: [modules/payload_deliverer](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/payload_deliverer) - ### Description + Handles payload delivery with either Gripper or a Winch with an appropriate timeout / feedback sensor setting, and communicates back the delivery result as an acknowledgement internally - ### Usage {#payload_deliverer_usage} ``` @@ -505,6 +518,7 @@ payload_deliverer [arguments...] Source: [systemcmds/perf](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/perf) Tool to print performance counters + ### Usage {#perf_usage} ``` @@ -521,6 +535,7 @@ perf [arguments...] Source: [systemcmds/reboot](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/reboot) Reboot the system + ### Usage {#reboot_usage} ``` @@ -535,6 +550,7 @@ reboot [arguments...] Source: [systemcmds/sd_bench](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_bench) Test the speed of an SD Card + ### Usage {#sd_bench_usage} ``` @@ -557,6 +573,7 @@ sd_bench [arguments...] Source: [systemcmds/sd_stress](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/sd_stress) Test operations on an SD Card + ### Usage {#sd_stress_usage} ``` @@ -592,7 +609,6 @@ serial_passthru [arguments...] Source: [systemcmds/system_time](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/system_time) - ### Description Command-line tool to set and get system time. @@ -600,6 +616,7 @@ Command-line tool to set and get system time. ### Examples Set the system time and read it back + ``` system_time set 1600775044 system_time get @@ -620,6 +637,7 @@ system_time [arguments...] Source: [systemcmds/top](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/top) Monitor running processes and their CPU, stack usage, priority and state + ### Usage {#top_usage} ``` @@ -633,6 +651,7 @@ Source: [systemcmds/usb_connected](https://github.com/PX4/PX4-Autopilot/tree/mai Utility to check if USB is connected. Was previously used in startup scripts. A return value of 0 means USB is connected, 1 otherwise. + ### Usage {#usb_connected_usage} ``` @@ -644,6 +663,7 @@ usb_connected [arguments...] Source: [systemcmds/ver](https://github.com/PX4/PX4-Autopilot/tree/main/src/systemcmds/ver) Tool to print various version information + ### Usage {#ver_usage} ``` diff --git a/docs/en/modules/modules_controller.md b/docs/en/modules/modules_controller.md index f2a6e3a484d1..bf0809017aa9 100644 --- a/docs/en/modules/modules_controller.md +++ b/docs/en/modules/modules_controller.md @@ -186,30 +186,6 @@ mc_att_control [arguments...] status print status info ``` -## mc_nn_control - -Source: [modules/mc_nn_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_nn_control) - -### Description - -Multicopter Neural Network Control module. -This module is an end-to-end neural network control system for multicopters. -It takes in 15 input values and outputs 4 control actions. -Inputs: [pos_err(3), att(6), vel(3), ang_vel(3)] -Outputs: [Actuator motors(4)] - -### Usage {#mc_nn_control_usage} - -``` -mc_nn_control [arguments...] - Commands: - start - - stop - - status print status info -``` - ## mc_pos_control Source: [modules/mc_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_pos_control) @@ -354,6 +330,46 @@ rover_mecanum [arguments...] status print status info ``` +## rover_pos_control + +Source: [modules/rover_pos_control](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/rover_pos_control) + +### Description + +Controls the position of a ground rover using an L1 controller. + +Publishes `vehicle_thrust_setpoint (only in x) and vehicle_torque_setpoint (only yaw)` messages at IMU_GYRO_RATEMAX. + +### Implementation + +Currently, this implementation supports only a few modes: + +- Full manual: Throttle and yaw controls are passed directly through to the actuators +- Auto mission: The rover runs missions +- Loiter: The rover will navigate to within the loiter radius, then stop the motors + +### Examples + +CLI usage example: + +``` +rover_pos_control start +rover_pos_control status +rover_pos_control stop +``` + +### Usage {#rover_pos_control_usage} + +``` +rover_pos_control [arguments...] + Commands: + start + + stop + + status print status info +``` + ## spacecraft Source: [modules/spacecraft](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/spacecraft) @@ -370,8 +386,6 @@ spacecraft [arguments...] Commands: start - status - stop status print status info diff --git a/docs/en/modules/modules_driver.md b/docs/en/modules/modules_driver.md index f4ebd987eb93..22d1ba9a8019 100644 --- a/docs/en/modules/modules_driver.md +++ b/docs/en/modules/modules_driver.md @@ -1109,7 +1109,7 @@ px4io [arguments...] ## rgbled -Source: [drivers/lights/rgbled_ncp5623c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled_ncp5623c) +Source: [drivers/lights/rgbled](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/lights/rgbled) ### Usage {#rgbled_usage} @@ -1124,9 +1124,7 @@ rgbled [arguments...] [-f ] bus frequency in kHz [-q] quiet startup (no message if no device found) [-a ] I2C address - default: 57 - [-o ] RGB PWM Assignment - default: 123 + default: 85 stop diff --git a/docs/en/modules/modules_driver_airspeed_sensor.md b/docs/en/modules/modules_driver_airspeed_sensor.md index a1545bfe5373..efab35a02a50 100644 --- a/docs/en/modules/modules_driver_airspeed_sensor.md +++ b/docs/en/modules/modules_driver_airspeed_sensor.md @@ -4,8 +4,8 @@ Source: [drivers/differential_pressure/asp5033](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/differential_pressure/asp5033) - ### Description + Driver to enable an external [ASP5033] (https://www.qio-tek.com/index.php/product/qiotek-asp5033-dronecan-airspeed-and-compass-module/) TE connected via I2C. diff --git a/docs/en/modules/modules_driver_camera.md b/docs/en/modules/modules_driver_camera.md index 58f3cfb45d65..c63df4619f84 100644 --- a/docs/en/modules/modules_driver_camera.md +++ b/docs/en/modules/modules_driver_camera.md @@ -4,7 +4,6 @@ Source: [drivers/camera_trigger](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/camera_trigger) - ### Description Camera trigger driver. diff --git a/docs/en/modules/modules_driver_distance_sensor.md b/docs/en/modules/modules_driver_distance_sensor.md index 4e78a7e7ff6a..db11c38e0e67 100644 --- a/docs/en/modules/modules_driver_distance_sensor.md +++ b/docs/en/modules/modules_driver_distance_sensor.md @@ -32,6 +32,8 @@ afbrs50 [arguments...] [-r ] Sensor rotation - downward facing by default default: 25 + test Test driver + stop Stop driver ``` @@ -104,7 +106,7 @@ Source: [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4 ### Description -I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20, SF30/d. +I2C bus driver for Lightware SFxx series LIDAR rangefinders: SF10/a, SF10/b, SF10/c, SF11/c, SF/LW20. Setup/usage information: https://docs.px4.io/main/en/sensor/sfxx_lidar.html @@ -238,32 +240,6 @@ ll40ls [arguments...] status print status info ``` -## ll40ls_pwm - -Source: [drivers/distance_sensor/ll40ls_pwm](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/ll40ls_pwm) - -### Description - -PWM driver for LidarLite rangefinders. - -The sensor/driver must be enabled using the parameter SENS_EN_LL40LS. - -Setup/usage information: https://docs.px4.io/main/en/sensor/lidar_lite.html - -### Usage {#ll40ls_pwm_usage} - -``` -ll40ls_pwm [arguments...] - Commands: - start Start driver - [-R ] Sensor rotation - downward facing by default - default: 25 - - status Print driver status information - - stop Stop driver -``` - ## mappydot Source: [drivers/distance_sensor/mappydot](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/mappydot) diff --git a/docs/en/modules/modules_driver_optical_flow.md b/docs/en/modules/modules_driver_optical_flow.md index 2c734b5c3f73..d69b6d28ccdc 100644 --- a/docs/en/modules/modules_driver_optical_flow.md +++ b/docs/en/modules/modules_driver_optical_flow.md @@ -4,7 +4,6 @@ Source: [drivers/optical_flow/thoneflow](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/optical_flow/thoneflow) - ### Description Serial bus driver for the ThoneFlow-3901U optical flow sensor. @@ -16,10 +15,13 @@ Setup/usage information: https://docs.px4.io/main/en/sensor/pmw3901.html#thone-t ### Examples Attempt to start driver on a specified serial device. + ``` thoneflow start -d /dev/ttyS1 ``` + Stop driver + ``` thoneflow stop ``` diff --git a/docs/en/modules/modules_driver_transponder.md b/docs/en/modules/modules_driver_transponder.md index 799f9a917929..dd9e4bdeceb6 100644 --- a/docs/en/modules/modules_driver_transponder.md +++ b/docs/en/modules/modules_driver_transponder.md @@ -4,25 +4,24 @@ Source: [drivers/transponder/sagetech_mxs](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/transponder/sagetech_mxs) + ### Description - ### Description + This driver integrates the Sagetech MXS Certified Transponder to send and receive ADSB messages and traffic. - This driver integrates the Sagetech MXS Certified Transponder to send and receive ADSB messages and traffic. + ### Examples - ### Examples + Attempt to start driver on a specified serial device. + $ sagetech_mxs start -d /dev/ttyS1 + Stop driver + $ sagetech_mxs stop + Set Flight ID (8 char max) + $ sagetech_mxs flight_id MXS12345 + Set MXS Operating Mode + $ sagetech_mxs opmode off/on/stby/alt + $ sagetech_mxs opmode 0/1/2/3 + Set the Squawk Code + $ sagetech_mxs squawk 1200 - Attempt to start driver on a specified serial device. - $ sagetech_mxs start -d /dev/ttyS1 - Stop driver - $ sagetech_mxs stop - Set Flight ID (8 char max) - $ sagetech_mxs flight_id MXS12345 - Set MXS Operating Mode - $ sagetech_mxs opmode off/on/stby/alt - $ sagetech_mxs opmode 0/1/2/3 - Set the Squawk Code - $ sagetech_mxs squawk 1200 - ### Usage {#sagetech_mxs_usage} ``` diff --git a/docs/en/modules/modules_estimator.md b/docs/en/modules/modules_estimator.md index 71041bcd5085..8186889dd4f5 100644 --- a/docs/en/modules/modules_estimator.md +++ b/docs/en/modules/modules_estimator.md @@ -1,15 +1,12 @@ # Modules Reference: Estimator - - ## AttitudeEstimatorQ Source: [modules/attitude_estimator_q](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/attitude_estimator_q) - ### Description -Attitude estimator q. +Attitude estimator q. ### Usage {#AttitudeEstimatorQ_usage} @@ -27,8 +24,8 @@ AttitudeEstimatorQ [arguments...] Source: [modules/airspeed_selector](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/airspeed_selector) - ### Description + This module provides a single airspeed_validated topic, containing indicated (IAS), calibrated (CAS), true airspeed (TAS) and the information if the estimation currently is invalid and if based sensor readings or on groundspeed minus windspeed. @@ -37,7 +34,6 @@ to a valid sensor in case of failure detection. For failure detection as well as the estimation of a scale factor from IAS to CAS, it runs several wind estimators and also publishes those. - ### Usage {#airspeed_estimator_usage} ``` @@ -54,8 +50,8 @@ airspeed_estimator [arguments...] Source: [modules/ekf2](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/ekf2) - ### Description + Attitude and position estimator using an Extended Kalman Filter. It is used for Multirotors and Fixed-Wing. The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.px4.io/main/en/advanced_config/tuning_the_ecl_ekf.html) page. @@ -63,7 +59,6 @@ The documentation can be found on the [ECL/EKF Overview & Tuning](https://docs.p ekf2 can be started in replay mode (`-r`): in this mode, it does not access the system time, but only uses the timestamps from the sensor topics. - ### Usage {#ekf2_usage} ``` @@ -85,10 +80,9 @@ ekf2 [arguments...] Source: [modules/local_position_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/local_position_estimator) - ### Description -Attitude and position estimator using an Extended Kalman Filter. +Attitude and position estimator using an Extended Kalman Filter. ### Usage {#local_position_estimator_usage} @@ -106,10 +100,8 @@ local_position_estimator [arguments...] Source: [modules/mc_hover_thrust_estimator](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/mc_hover_thrust_estimator) - ### Description - ### Usage {#mc_hover_thrust_estimator_usage} ``` diff --git a/docs/en/modules/modules_main.md b/docs/en/modules/modules_main.md index 34e325dcd21e..4403a1ffa566 100644 --- a/docs/en/modules/modules_main.md +++ b/docs/en/modules/modules_main.md @@ -1,4 +1,3 @@ - # Modules & Commands Reference The following pages document the PX4 modules, drivers and commands. @@ -21,9 +20,11 @@ the root of the PX4-Autopilot directory: ``` make module_documentation ``` + The generated files will be written to the `modules` directory. ## Categories + - [Autotune](modules_autotune.md) - [Command](modules_command.md) - [Communication](modules_communication.md) diff --git a/docs/en/modules/modules_simulation.md b/docs/en/modules/modules_simulation.md index 18c267517b0f..f0a12f66048a 100644 --- a/docs/en/modules/modules_simulation.md +++ b/docs/en/modules/modules_simulation.md @@ -1,13 +1,11 @@ # Modules Reference: Simulation - - ## simulator_sih Source: [modules/simulation/simulator_sih](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih) - ### Description + This module provides a simulator for quadrotors and fixed-wings running fully inside the hardware autopilot. @@ -18,13 +16,12 @@ This simulator publishes the sensors signals corrupted with realistic noise in order to incorporate the state estimator in the loop. ### Implementation + The simulator implements the equations of motion using matrix algebra. Quaternion representation is used for the attitude. Forward Euler is used for integration. Most of the variables are declared global in the .hpp file to avoid stack overflow. - - ### Usage {#simulator_sih_usage} ``` diff --git a/docs/en/modules/modules_system.md b/docs/en/modules/modules_system.md index fe9b467cf60d..8df94803e4cd 100644 --- a/docs/en/modules/modules_system.md +++ b/docs/en/modules/modules_system.md @@ -127,10 +127,6 @@ commander [arguments...] check Run preflight checks - safety Change prearm safety state - on|off [on] to activate safety, [off] to deactivate safety and allow - control surface movements - arm [-f] Force arming (do not run preflight checks) @@ -144,13 +140,13 @@ commander [arguments...] transition VTOL transition mode Change flight mode - manual|acro|offboard|stabilized|altctl|posctl|altitude_cruise|position:slow - |auto:mission|auto:loiter|auto:rtl|auto:takeoff|auto:land|auto: - precland|ext1 Flight mode + manual|acro|offboard|stabilized|altctl|posctl|position:slow|auto:mission|au + to:loiter|auto:rtl|auto:takeoff|auto:land|auto:precland|ext1 + Flight mode pair - termination + lockdown on|off Turn lockdown on or off set_ekf_origin @@ -158,9 +154,6 @@ commander [arguments...] lat|lon|alt Origin latitude longitude altitude - set_heading Set current heading - heading degrees from True North [0 360] - poweroff Power off board (if supported) stop @@ -288,33 +281,6 @@ gyro_fft [arguments...] status print status info ``` -## hardfault_stream - -Source: [modules/hardfault_stream](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/hardfault_stream) - -### Description - -Background process that streams the latest hardfault via MAVLink. - -The module is especially useful when it is necessary to quickly push a hard fault to the ground station. -This is useful in cases where the drone experiences a hard fault during flight. -It ensures that some data is retained in case the permanent storage is destroyed during a crash. - -To reliably stream, it is necessary to send the STATUSTEXT message via MAVLink at a -high enough frequency. The recommended frequency is 10 Hz or higher. - -### Usage {#hardfault_stream_usage} - -``` -hardfault_stream [arguments...] - Commands: - start Start the background task - - stop - - status print status info -``` - ## heater Source: [drivers/heater](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/heater) @@ -1069,9 +1035,7 @@ uxrce_dds_client [arguments...] values: [-p ] Agent listening port. If not provided, defaults to UXRCE_DDS_PRT - [-n ] Client DDS namespace. If not provided but UXRCE_DDS_NS_IDX is - between 0 and 9999 inclusive, then uav_ + UXRCE_DDS_NS_IDX will - be used + [-n ] Client DDS namespace stop diff --git a/docs/en/modules/modules_template.md b/docs/en/modules/modules_template.md index 523d9ff02bba..cb4e22fe082c 100644 --- a/docs/en/modules/modules_template.md +++ b/docs/en/modules/modules_template.md @@ -1,27 +1,27 @@ # Modules Reference: Template - - ## module Source: [templates/template_module](https://github.com/PX4/PX4-Autopilot/tree/main/src/templates/template_module) - ### Description + Section that describes the provided module functionality. This is a template for a module running as a task in the background with start/stop/status functionality. ### Implementation + Section describing the high-level implementation of this module. ### Examples + CLI usage example: + ``` module start -f -p 42 ``` - ### Usage {#module_usage} ``` @@ -41,10 +41,9 @@ module [arguments...] Source: [examples/work_item](https://github.com/PX4/PX4-Autopilot/tree/main/src/examples/work_item) - ### Description -Example of a simple module running out of a work queue. +Example of a simple module running out of a work queue. ### Usage {#work_item_example_usage} diff --git a/docs/en/msg_docs/ActuatorControlsStatus.md b/docs/en/msg_docs/ActuatorControlsStatus.md index 2eb1d53f2204..e8b30d6132af 100644 --- a/docs/en/msg_docs/ActuatorControlsStatus.md +++ b/docs/en/msg_docs/ActuatorControlsStatus.md @@ -1,7 +1,5 @@ # ActuatorControlsStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg) ```c diff --git a/docs/en/msg_docs/ActuatorOutputs.md b/docs/en/msg_docs/ActuatorOutputs.md index 3fc4a94c9d21..cf890049823a 100644 --- a/docs/en/msg_docs/ActuatorOutputs.md +++ b/docs/en/msg_docs/ActuatorOutputs.md @@ -1,7 +1,5 @@ # ActuatorOutputs (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg) ```c diff --git a/docs/en/msg_docs/ActuatorTest.md b/docs/en/msg_docs/ActuatorTest.md index 923d82977493..16d1523c9d47 100644 --- a/docs/en/msg_docs/ActuatorTest.md +++ b/docs/en/msg_docs/ActuatorTest.md @@ -1,7 +1,5 @@ # ActuatorTest (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorTest.msg) ```c diff --git a/docs/en/msg_docs/AirspeedValidatedV0.md b/docs/en/msg_docs/AirspeedValidatedV0.md index 9cd392a955ac..8bca98a22473 100644 --- a/docs/en/msg_docs/AirspeedValidatedV0.md +++ b/docs/en/msg_docs/AirspeedValidatedV0.md @@ -1,7 +1,5 @@ # AirspeedValidatedV0 (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/AirspeedValidatedV0.msg) ```c diff --git a/docs/en/msg_docs/ArmingCheckReply.md b/docs/en/msg_docs/ArmingCheckReply.md index 14af54f0d146..d5e3322506bc 100644 --- a/docs/en/msg_docs/ArmingCheckReply.md +++ b/docs/en/msg_docs/ArmingCheckReply.md @@ -1,6 +1,6 @@ # ArmingCheckReply (UORB message) -Arming check reply +Arming check reply. This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -12,7 +12,7 @@ The message is not used by internal/FMU components, as their mode requirements a [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckReply.msg) ```c -# Arming check reply +# Arming check reply. # # This is a response to an ArmingCheckRequest message sent by the FMU to an external component, such as a ROS 2 navigation mode. # The response contains the current set of external mode requirements, and a queue of events indicating recent failures to set the mode (which the FMU may then forward to a ground station). @@ -21,39 +21,39 @@ The message is not used by internal/FMU components, as their mode requirements a # Note that the external component is identified by its registration_id, which is allocated to the component during registration (arming_check_id in RegisterExtComponentReply). # The message is not used by internal/FMU components, as their mode requirements are known at compile time. -uint32 MESSAGE_VERSION = 1 +uint32 MESSAGE_VERSION = 1 uint64 timestamp # [us] Time since system start. -uint8 request_id # [-] Id of ArmingCheckRequest for which this is a response -uint8 registration_id # [-] Id of external component emitting this response +uint8 request_id # Id of ArmingCheckRequest for which this is a response. +uint8 registration_id # Id of external component emitting this response. -uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies +uint8 HEALTH_COMPONENT_INDEX_NONE = 0 # Index of health component for which this response applies. -uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] -bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json) -bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json) -bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json) +uint8 health_component_index # [@enum HEALTH_COMPONENT_INDEX] +bool health_component_is_present # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_warning # Unused. Intended for use with health events interface (health_component_t in events.json). +bool health_component_error # Unused. Intended for use with health events interface (health_component_t in events.json). -bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed +bool can_arm_and_run # True if the component can arm. For navigation mode components, true if the component can arm in the mode or switch to the mode when already armed. -uint8 num_events # Number of queued failure messages (Event) in the events field +uint8 num_events # Number of queued failure messages (Event) in the events field. -Event[5] events # Arming failure reasons (Queue of events to report to GCS) +Event[5] events # Arming failure reasons (Queue of events to report to GCS). # Mode requirements -bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope) -bool mode_req_attitude # Requires an attitude estimate -bool mode_req_local_alt # Requires a local altitude estimate -bool mode_req_local_position # Requires a local position estimate -bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate -bool mode_req_global_position # Requires a global position estimate -bool mode_req_global_position_relaxed # Requires a relaxed global position estimate -bool mode_req_mission # Requires an uploaded mission -bool mode_req_home_position # Requires a home position (such as RTL/Return mode) -bool mode_req_prevent_arming # Prevent arming (such as in Land mode) -bool mode_req_manual_control # Requires a manual controller - -uint8 ORB_QUEUE_LENGTH = 4 +bool mode_req_angular_velocity # Requires angular velocity estimate (e.g. from gyroscope). +bool mode_req_attitude # Requires an attitude estimate. +bool mode_req_local_alt # Requires a local altitude estimate. +bool mode_req_local_position # Requires a local position estimate. +bool mode_req_local_position_relaxed # Requires a more relaxed global position estimate. +bool mode_req_global_position # Requires a global position estimate. +bool mode_req_global_position_relaxed # Requires a relaxed global position estimate. +bool mode_req_mission # Requires an uploaded mission. +bool mode_req_home_position # Requires a home position (such as RTL/Return mode). +bool mode_req_prevent_arming # Prevent arming (such as in Land mode). +bool mode_req_manual_control # Requires a manual controller + +uint8 ORB_QUEUE_LENGTH = 4 # ``` diff --git a/docs/en/msg_docs/ArmingCheckRequest.md b/docs/en/msg_docs/ArmingCheckRequest.md index d093dfb5e17b..cfa4b52c235c 100644 --- a/docs/en/msg_docs/ArmingCheckRequest.md +++ b/docs/en/msg_docs/ArmingCheckRequest.md @@ -1,6 +1,6 @@ # ArmingCheckRequest (UORB message) -Arming check request +Arming check request. Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -12,7 +12,7 @@ The reply will also include the registration_id for each external component, pro [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ArmingCheckRequest.msg) ```c -# Arming check request +# Arming check request. # # Broadcast message to request arming checks be reported by all registered components, such as external ROS 2 navigation modes. # All registered components should respond with an ArmingCheckReply message that indicates their current mode requirements, and any arming failure information. @@ -21,12 +21,10 @@ The reply will also include the registration_id for each external component, pro # The reply will include the published request_id, allowing correlation of all arming check information for a particular request. # The reply will also include the registration_id for each external component, provided to it during the registration process (RegisterExtComponentReply). -uint32 MESSAGE_VERSION = 1 +uint32 MESSAGE_VERSION = 0 -uint64 timestamp # [us] Time since system start +uint64 timestamp # [us] Time since system start. -uint8 request_id # [-] Id of this request. Allows correlation with associated ArmingCheckReply messages. - -uint32 valid_registrations_mask # [-] Bitmask of valid registration ID's (the bit is also cleared if flagged as unresponsive) +uint8 request_id # Id of this request. Allows correlation with associated ArmingCheckReply messages. ``` diff --git a/docs/en/msg_docs/ButtonEvent.md b/docs/en/msg_docs/ButtonEvent.md index 967f694fa622..8c22ff24915e 100644 --- a/docs/en/msg_docs/ButtonEvent.md +++ b/docs/en/msg_docs/ButtonEvent.md @@ -1,7 +1,5 @@ # ButtonEvent (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg) ```c diff --git a/docs/en/msg_docs/CameraCapture.md b/docs/en/msg_docs/CameraCapture.md index fb73e3045869..cafef279228b 100644 --- a/docs/en/msg_docs/CameraCapture.md +++ b/docs/en/msg_docs/CameraCapture.md @@ -1,7 +1,5 @@ # CameraCapture (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraCapture.msg) ```c diff --git a/docs/en/msg_docs/CameraStatus.md b/docs/en/msg_docs/CameraStatus.md index 1bf6d3b33cb6..2ed1011c5069 100644 --- a/docs/en/msg_docs/CameraStatus.md +++ b/docs/en/msg_docs/CameraStatus.md @@ -1,7 +1,5 @@ # CameraStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraStatus.msg) ```c diff --git a/docs/en/msg_docs/CameraTrigger.md b/docs/en/msg_docs/CameraTrigger.md index a1949a75697d..edd07edd5a8c 100644 --- a/docs/en/msg_docs/CameraTrigger.md +++ b/docs/en/msg_docs/CameraTrigger.md @@ -1,7 +1,5 @@ # CameraTrigger (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CameraTrigger.msg) ```c diff --git a/docs/en/msg_docs/CanInterfaceStatus.md b/docs/en/msg_docs/CanInterfaceStatus.md index 234ade997d03..1d0f618f8d08 100644 --- a/docs/en/msg_docs/CanInterfaceStatus.md +++ b/docs/en/msg_docs/CanInterfaceStatus.md @@ -1,7 +1,5 @@ # CanInterfaceStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/CanInterfaceStatus.msg) ```c diff --git a/docs/en/msg_docs/Cpuload.md b/docs/en/msg_docs/Cpuload.md index 84f8447c3911..fd865702a8ab 100644 --- a/docs/en/msg_docs/Cpuload.md +++ b/docs/en/msg_docs/Cpuload.md @@ -1,7 +1,5 @@ # Cpuload (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Cpuload.msg) ```c diff --git a/docs/en/msg_docs/DatamanRequest.md b/docs/en/msg_docs/DatamanRequest.md index 06d1c5d8b7d7..ae8701f157b4 100644 --- a/docs/en/msg_docs/DatamanRequest.md +++ b/docs/en/msg_docs/DatamanRequest.md @@ -1,7 +1,5 @@ # DatamanRequest (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DatamanRequest.msg) ```c diff --git a/docs/en/msg_docs/DatamanResponse.md b/docs/en/msg_docs/DatamanResponse.md index 3857d85c69ae..e8cd9f5c71c8 100644 --- a/docs/en/msg_docs/DatamanResponse.md +++ b/docs/en/msg_docs/DatamanResponse.md @@ -1,7 +1,5 @@ # DatamanResponse (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DatamanResponse.msg) ```c diff --git a/docs/en/msg_docs/DebugArray.md b/docs/en/msg_docs/DebugArray.md index 7dc20d00e365..1e1cacd73908 100644 --- a/docs/en/msg_docs/DebugArray.md +++ b/docs/en/msg_docs/DebugArray.md @@ -1,7 +1,5 @@ # DebugArray (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugArray.msg) ```c diff --git a/docs/en/msg_docs/DebugKeyValue.md b/docs/en/msg_docs/DebugKeyValue.md index ea5709c88e38..f9d6a5bde25a 100644 --- a/docs/en/msg_docs/DebugKeyValue.md +++ b/docs/en/msg_docs/DebugKeyValue.md @@ -1,7 +1,5 @@ # DebugKeyValue (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugKeyValue.msg) ```c diff --git a/docs/en/msg_docs/DebugValue.md b/docs/en/msg_docs/DebugValue.md index 8c86a763a48c..04457e37cc93 100644 --- a/docs/en/msg_docs/DebugValue.md +++ b/docs/en/msg_docs/DebugValue.md @@ -1,7 +1,5 @@ # DebugValue (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugValue.msg) ```c diff --git a/docs/en/msg_docs/DebugVect.md b/docs/en/msg_docs/DebugVect.md index 31e1c8d044c4..ec009e7279f5 100644 --- a/docs/en/msg_docs/DebugVect.md +++ b/docs/en/msg_docs/DebugVect.md @@ -1,7 +1,5 @@ # DebugVect (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DebugVect.msg) ```c diff --git a/docs/en/msg_docs/DistanceSensorModeChangeRequest.md b/docs/en/msg_docs/DistanceSensorModeChangeRequest.md index 56ed7e1bbad3..ab957de1336f 100644 --- a/docs/en/msg_docs/DistanceSensorModeChangeRequest.md +++ b/docs/en/msg_docs/DistanceSensorModeChangeRequest.md @@ -1,7 +1,5 @@ # DistanceSensorModeChangeRequest (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/DistanceSensorModeChangeRequest.msg) ```c diff --git a/docs/en/msg_docs/EscStatus.md b/docs/en/msg_docs/EscStatus.md index 07bd468ceebe..97ca47556867 100644 --- a/docs/en/msg_docs/EscStatus.md +++ b/docs/en/msg_docs/EscStatus.md @@ -1,7 +1,5 @@ # EscStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EscStatus.msg) ```c diff --git a/docs/en/msg_docs/EstimatorAidSource1d.md b/docs/en/msg_docs/EstimatorAidSource1d.md index 45d0659de2f6..da73b0859f8f 100644 --- a/docs/en/msg_docs/EstimatorAidSource1d.md +++ b/docs/en/msg_docs/EstimatorAidSource1d.md @@ -1,7 +1,5 @@ # EstimatorAidSource1d (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg) ```c diff --git a/docs/en/msg_docs/EstimatorAidSource2d.md b/docs/en/msg_docs/EstimatorAidSource2d.md index 70cc2948e597..9714e3491d08 100644 --- a/docs/en/msg_docs/EstimatorAidSource2d.md +++ b/docs/en/msg_docs/EstimatorAidSource2d.md @@ -1,7 +1,5 @@ # EstimatorAidSource2d (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg) ```c diff --git a/docs/en/msg_docs/EstimatorAidSource3d.md b/docs/en/msg_docs/EstimatorAidSource3d.md index 457deec9c93e..69b38719a306 100644 --- a/docs/en/msg_docs/EstimatorAidSource3d.md +++ b/docs/en/msg_docs/EstimatorAidSource3d.md @@ -1,7 +1,5 @@ # EstimatorAidSource3d (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource3d.msg) ```c diff --git a/docs/en/msg_docs/EstimatorBias.md b/docs/en/msg_docs/EstimatorBias.md index 3b7408be15fe..fa911d05b89e 100644 --- a/docs/en/msg_docs/EstimatorBias.md +++ b/docs/en/msg_docs/EstimatorBias.md @@ -1,7 +1,5 @@ # EstimatorBias (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorBias.msg) ```c diff --git a/docs/en/msg_docs/EstimatorBias3d.md b/docs/en/msg_docs/EstimatorBias3d.md index af89bab69f2c..7fff18ae251d 100644 --- a/docs/en/msg_docs/EstimatorBias3d.md +++ b/docs/en/msg_docs/EstimatorBias3d.md @@ -1,7 +1,5 @@ # EstimatorBias3d (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorBias3d.msg) ```c diff --git a/docs/en/msg_docs/EstimatorEventFlags.md b/docs/en/msg_docs/EstimatorEventFlags.md index c56f29a84218..54f333d78837 100644 --- a/docs/en/msg_docs/EstimatorEventFlags.md +++ b/docs/en/msg_docs/EstimatorEventFlags.md @@ -1,7 +1,5 @@ # EstimatorEventFlags (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorEventFlags.msg) ```c diff --git a/docs/en/msg_docs/EstimatorGpsStatus.md b/docs/en/msg_docs/EstimatorGpsStatus.md index e25be3e558b9..1833682def70 100644 --- a/docs/en/msg_docs/EstimatorGpsStatus.md +++ b/docs/en/msg_docs/EstimatorGpsStatus.md @@ -1,7 +1,5 @@ # EstimatorGpsStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorGpsStatus.msg) ```c diff --git a/docs/en/msg_docs/EstimatorInnovations.md b/docs/en/msg_docs/EstimatorInnovations.md index 478fe79831d9..59014ef15b9f 100644 --- a/docs/en/msg_docs/EstimatorInnovations.md +++ b/docs/en/msg_docs/EstimatorInnovations.md @@ -1,7 +1,5 @@ # EstimatorInnovations (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorInnovations.msg) ```c diff --git a/docs/en/msg_docs/EstimatorSelectorStatus.md b/docs/en/msg_docs/EstimatorSelectorStatus.md index 3e64205a8f7a..fd1145e2dc68 100644 --- a/docs/en/msg_docs/EstimatorSelectorStatus.md +++ b/docs/en/msg_docs/EstimatorSelectorStatus.md @@ -1,7 +1,5 @@ # EstimatorSelectorStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorSelectorStatus.msg) ```c diff --git a/docs/en/msg_docs/EstimatorStates.md b/docs/en/msg_docs/EstimatorStates.md index b3a343217ba0..7d13493ca9f3 100644 --- a/docs/en/msg_docs/EstimatorStates.md +++ b/docs/en/msg_docs/EstimatorStates.md @@ -1,7 +1,5 @@ # EstimatorStates (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorStates.msg) ```c diff --git a/docs/en/msg_docs/FigureEightStatus.md b/docs/en/msg_docs/FigureEightStatus.md index 5487490804dd..7a8ae760c227 100644 --- a/docs/en/msg_docs/FigureEightStatus.md +++ b/docs/en/msg_docs/FigureEightStatus.md @@ -1,7 +1,5 @@ # FigureEightStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FigureEightStatus.msg) ```c diff --git a/docs/en/msg_docs/FlightPhaseEstimation.md b/docs/en/msg_docs/FlightPhaseEstimation.md index b3d9147e28b0..51561e39e387 100644 --- a/docs/en/msg_docs/FlightPhaseEstimation.md +++ b/docs/en/msg_docs/FlightPhaseEstimation.md @@ -1,7 +1,5 @@ # FlightPhaseEstimation (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FlightPhaseEstimation.msg) ```c diff --git a/docs/en/msg_docs/FollowTarget.md b/docs/en/msg_docs/FollowTarget.md index e9086f27d63b..ae194a60195e 100644 --- a/docs/en/msg_docs/FollowTarget.md +++ b/docs/en/msg_docs/FollowTarget.md @@ -1,7 +1,5 @@ # FollowTarget (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTarget.msg) ```c diff --git a/docs/en/msg_docs/FollowTargetEstimator.md b/docs/en/msg_docs/FollowTargetEstimator.md index e118475f4120..00d5760b36fa 100644 --- a/docs/en/msg_docs/FollowTargetEstimator.md +++ b/docs/en/msg_docs/FollowTargetEstimator.md @@ -1,7 +1,5 @@ # FollowTargetEstimator (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTargetEstimator.msg) ```c diff --git a/docs/en/msg_docs/FollowTargetStatus.md b/docs/en/msg_docs/FollowTargetStatus.md index 7f24cc1dd5b5..99594c5fcb7c 100644 --- a/docs/en/msg_docs/FollowTargetStatus.md +++ b/docs/en/msg_docs/FollowTargetStatus.md @@ -1,7 +1,5 @@ # FollowTargetStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FollowTargetStatus.msg) ```c diff --git a/docs/en/msg_docs/FuelTankStatus.md b/docs/en/msg_docs/FuelTankStatus.md index 608999e84c94..f36eaff6dce9 100644 --- a/docs/en/msg_docs/FuelTankStatus.md +++ b/docs/en/msg_docs/FuelTankStatus.md @@ -1,7 +1,5 @@ # FuelTankStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/FuelTankStatus.msg) ```c diff --git a/docs/en/msg_docs/GeneratorStatus.md b/docs/en/msg_docs/GeneratorStatus.md index 159221547f4a..b21bc9852a38 100644 --- a/docs/en/msg_docs/GeneratorStatus.md +++ b/docs/en/msg_docs/GeneratorStatus.md @@ -1,7 +1,5 @@ # GeneratorStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeneratorStatus.msg) ```c diff --git a/docs/en/msg_docs/GeofenceResult.md b/docs/en/msg_docs/GeofenceResult.md index f54a2f99425f..1259594be7f2 100644 --- a/docs/en/msg_docs/GeofenceResult.md +++ b/docs/en/msg_docs/GeofenceResult.md @@ -1,7 +1,5 @@ # GeofenceResult (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeofenceResult.msg) ```c diff --git a/docs/en/msg_docs/GeofenceStatus.md b/docs/en/msg_docs/GeofenceStatus.md index 298fd31ba6ab..9918290e4df2 100644 --- a/docs/en/msg_docs/GeofenceStatus.md +++ b/docs/en/msg_docs/GeofenceStatus.md @@ -1,7 +1,5 @@ # GeofenceStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GeofenceStatus.msg) ```c diff --git a/docs/en/msg_docs/GimbalControls.md b/docs/en/msg_docs/GimbalControls.md index cde183d443df..bc8408cffa21 100644 --- a/docs/en/msg_docs/GimbalControls.md +++ b/docs/en/msg_docs/GimbalControls.md @@ -1,7 +1,5 @@ # GimbalControls (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalControls.msg) ```c diff --git a/docs/en/msg_docs/GimbalDeviceInformation.md b/docs/en/msg_docs/GimbalDeviceInformation.md index fd727f4b8652..d06837a04905 100644 --- a/docs/en/msg_docs/GimbalDeviceInformation.md +++ b/docs/en/msg_docs/GimbalDeviceInformation.md @@ -1,7 +1,5 @@ # GimbalDeviceInformation (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceInformation.msg) ```c diff --git a/docs/en/msg_docs/GimbalDeviceSetAttitude.md b/docs/en/msg_docs/GimbalDeviceSetAttitude.md index 992153608408..d47cdf4689e1 100644 --- a/docs/en/msg_docs/GimbalDeviceSetAttitude.md +++ b/docs/en/msg_docs/GimbalDeviceSetAttitude.md @@ -1,7 +1,5 @@ # GimbalDeviceSetAttitude (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalDeviceSetAttitude.msg) ```c diff --git a/docs/en/msg_docs/GimbalManagerInformation.md b/docs/en/msg_docs/GimbalManagerInformation.md index ce60d2c5e08f..fab5d6a87e38 100644 --- a/docs/en/msg_docs/GimbalManagerInformation.md +++ b/docs/en/msg_docs/GimbalManagerInformation.md @@ -1,7 +1,5 @@ # GimbalManagerInformation (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerInformation.msg) ```c diff --git a/docs/en/msg_docs/GimbalManagerSetAttitude.md b/docs/en/msg_docs/GimbalManagerSetAttitude.md index 22c97eb74e9b..1415f34b4224 100644 --- a/docs/en/msg_docs/GimbalManagerSetAttitude.md +++ b/docs/en/msg_docs/GimbalManagerSetAttitude.md @@ -1,7 +1,5 @@ # GimbalManagerSetAttitude (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerSetAttitude.msg) ```c diff --git a/docs/en/msg_docs/GimbalManagerSetManualControl.md b/docs/en/msg_docs/GimbalManagerSetManualControl.md index c419917ba6a1..10ec82241555 100644 --- a/docs/en/msg_docs/GimbalManagerSetManualControl.md +++ b/docs/en/msg_docs/GimbalManagerSetManualControl.md @@ -1,7 +1,5 @@ # GimbalManagerSetManualControl (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerSetManualControl.msg) ```c diff --git a/docs/en/msg_docs/GimbalManagerStatus.md b/docs/en/msg_docs/GimbalManagerStatus.md index d0f741ad397f..317e1d35381d 100644 --- a/docs/en/msg_docs/GimbalManagerStatus.md +++ b/docs/en/msg_docs/GimbalManagerStatus.md @@ -1,7 +1,5 @@ # GimbalManagerStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GimbalManagerStatus.msg) ```c diff --git a/docs/en/msg_docs/GpsInjectData.md b/docs/en/msg_docs/GpsInjectData.md index 0eefd1da4093..2eda49d0c4eb 100644 --- a/docs/en/msg_docs/GpsInjectData.md +++ b/docs/en/msg_docs/GpsInjectData.md @@ -1,7 +1,5 @@ # GpsInjectData (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/GpsInjectData.msg) ```c diff --git a/docs/en/msg_docs/HealthReport.md b/docs/en/msg_docs/HealthReport.md index 447d9da62150..f69de0b179c6 100644 --- a/docs/en/msg_docs/HealthReport.md +++ b/docs/en/msg_docs/HealthReport.md @@ -1,7 +1,5 @@ # HealthReport (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HealthReport.msg) ```c diff --git a/docs/en/msg_docs/HeaterStatus.md b/docs/en/msg_docs/HeaterStatus.md index 3917f0242807..49194eed01aa 100644 --- a/docs/en/msg_docs/HeaterStatus.md +++ b/docs/en/msg_docs/HeaterStatus.md @@ -1,7 +1,5 @@ # HeaterStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HeaterStatus.msg) ```c diff --git a/docs/en/msg_docs/HoverThrustEstimate.md b/docs/en/msg_docs/HoverThrustEstimate.md index 8c0aa1eb83be..d84945da5817 100644 --- a/docs/en/msg_docs/HoverThrustEstimate.md +++ b/docs/en/msg_docs/HoverThrustEstimate.md @@ -1,7 +1,5 @@ # HoverThrustEstimate (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/HoverThrustEstimate.msg) ```c diff --git a/docs/en/msg_docs/InternalCombustionEngineStatus.md b/docs/en/msg_docs/InternalCombustionEngineStatus.md index 32642ea23e4e..2ebb28ef4dbe 100644 --- a/docs/en/msg_docs/InternalCombustionEngineStatus.md +++ b/docs/en/msg_docs/InternalCombustionEngineStatus.md @@ -1,7 +1,5 @@ # InternalCombustionEngineStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/InternalCombustionEngineStatus.msg) ```c diff --git a/docs/en/msg_docs/IridiumsbdStatus.md b/docs/en/msg_docs/IridiumsbdStatus.md index f2b76adc240f..07355178c91b 100644 --- a/docs/en/msg_docs/IridiumsbdStatus.md +++ b/docs/en/msg_docs/IridiumsbdStatus.md @@ -1,7 +1,5 @@ # IridiumsbdStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/IridiumsbdStatus.msg) ```c diff --git a/docs/en/msg_docs/LandingGear.md b/docs/en/msg_docs/LandingGear.md index 89b79a8b2c93..25e803e461e5 100644 --- a/docs/en/msg_docs/LandingGear.md +++ b/docs/en/msg_docs/LandingGear.md @@ -1,7 +1,5 @@ # LandingGear (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingGear.msg) ```c diff --git a/docs/en/msg_docs/LandingGearWheel.md b/docs/en/msg_docs/LandingGearWheel.md index 1c04a448bd53..74da2943fdec 100644 --- a/docs/en/msg_docs/LandingGearWheel.md +++ b/docs/en/msg_docs/LandingGearWheel.md @@ -1,7 +1,5 @@ # LandingGearWheel (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingGearWheel.msg) ```c diff --git a/docs/en/msg_docs/LandingTargetInnovations.md b/docs/en/msg_docs/LandingTargetInnovations.md index 29bc06bbc20e..9c896092e38f 100644 --- a/docs/en/msg_docs/LandingTargetInnovations.md +++ b/docs/en/msg_docs/LandingTargetInnovations.md @@ -1,7 +1,5 @@ # LandingTargetInnovations (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LandingTargetInnovations.msg) ```c diff --git a/docs/en/msg_docs/LoggerStatus.md b/docs/en/msg_docs/LoggerStatus.md index 63ca11485166..81dd11e035ca 100644 --- a/docs/en/msg_docs/LoggerStatus.md +++ b/docs/en/msg_docs/LoggerStatus.md @@ -1,7 +1,5 @@ # LoggerStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/LoggerStatus.msg) ```c diff --git a/docs/en/msg_docs/MagWorkerData.md b/docs/en/msg_docs/MagWorkerData.md index cb7103aaead6..d761c9284389 100644 --- a/docs/en/msg_docs/MagWorkerData.md +++ b/docs/en/msg_docs/MagWorkerData.md @@ -1,7 +1,5 @@ # MagWorkerData (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MagWorkerData.msg) ```c diff --git a/docs/en/msg_docs/MagnetometerBiasEstimate.md b/docs/en/msg_docs/MagnetometerBiasEstimate.md index 08f40114976d..0c8c28af9b8c 100644 --- a/docs/en/msg_docs/MagnetometerBiasEstimate.md +++ b/docs/en/msg_docs/MagnetometerBiasEstimate.md @@ -1,7 +1,5 @@ # MagnetometerBiasEstimate (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MagnetometerBiasEstimate.msg) ```c diff --git a/docs/en/msg_docs/ManualControlSetpoint.md b/docs/en/msg_docs/ManualControlSetpoint.md index a4f70d6738ca..b96cb643220d 100644 --- a/docs/en/msg_docs/ManualControlSetpoint.md +++ b/docs/en/msg_docs/ManualControlSetpoint.md @@ -1,7 +1,5 @@ # ManualControlSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/ManualControlSetpoint.msg) ```c diff --git a/docs/en/msg_docs/MavlinkLog.md b/docs/en/msg_docs/MavlinkLog.md index 91900aea1bfb..64ab9a808503 100644 --- a/docs/en/msg_docs/MavlinkLog.md +++ b/docs/en/msg_docs/MavlinkLog.md @@ -1,7 +1,5 @@ # MavlinkLog (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkLog.msg) ```c diff --git a/docs/en/msg_docs/MessageFormatRequest.md b/docs/en/msg_docs/MessageFormatRequest.md index 7c4675e3f683..a141574434e3 100644 --- a/docs/en/msg_docs/MessageFormatRequest.md +++ b/docs/en/msg_docs/MessageFormatRequest.md @@ -1,7 +1,5 @@ # MessageFormatRequest (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MessageFormatRequest.msg) ```c diff --git a/docs/en/msg_docs/MessageFormatResponse.md b/docs/en/msg_docs/MessageFormatResponse.md index 3a537289a064..5b9bd86917a9 100644 --- a/docs/en/msg_docs/MessageFormatResponse.md +++ b/docs/en/msg_docs/MessageFormatResponse.md @@ -1,7 +1,5 @@ # MessageFormatResponse (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MessageFormatResponse.msg) ```c diff --git a/docs/en/msg_docs/Mission.md b/docs/en/msg_docs/Mission.md index 139b2e89147a..d878aba5a676 100644 --- a/docs/en/msg_docs/Mission.md +++ b/docs/en/msg_docs/Mission.md @@ -1,7 +1,5 @@ # Mission (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Mission.msg) ```c diff --git a/docs/en/msg_docs/MissionResult.md b/docs/en/msg_docs/MissionResult.md index 325dc0e43834..60ee84c923b5 100644 --- a/docs/en/msg_docs/MissionResult.md +++ b/docs/en/msg_docs/MissionResult.md @@ -1,7 +1,5 @@ # MissionResult (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MissionResult.msg) ```c diff --git a/docs/en/msg_docs/MountOrientation.md b/docs/en/msg_docs/MountOrientation.md index dc676cb94b17..4ab3f5b3e491 100644 --- a/docs/en/msg_docs/MountOrientation.md +++ b/docs/en/msg_docs/MountOrientation.md @@ -1,7 +1,5 @@ # MountOrientation (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/MountOrientation.msg) ```c diff --git a/docs/en/msg_docs/NavigatorMissionItem.md b/docs/en/msg_docs/NavigatorMissionItem.md index 3c3bc3f58cf7..0899681c5435 100644 --- a/docs/en/msg_docs/NavigatorMissionItem.md +++ b/docs/en/msg_docs/NavigatorMissionItem.md @@ -1,7 +1,5 @@ # NavigatorMissionItem (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NavigatorMissionItem.msg) ```c diff --git a/docs/en/msg_docs/NormalizedUnsignedSetpoint.md b/docs/en/msg_docs/NormalizedUnsignedSetpoint.md index 025a5fae76fa..8533b090ae85 100644 --- a/docs/en/msg_docs/NormalizedUnsignedSetpoint.md +++ b/docs/en/msg_docs/NormalizedUnsignedSetpoint.md @@ -1,7 +1,5 @@ # NormalizedUnsignedSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg) ```c diff --git a/docs/en/msg_docs/OpenDroneIdArmStatus.md b/docs/en/msg_docs/OpenDroneIdArmStatus.md index 78c7992a11c6..152d34a1665b 100644 --- a/docs/en/msg_docs/OpenDroneIdArmStatus.md +++ b/docs/en/msg_docs/OpenDroneIdArmStatus.md @@ -1,7 +1,5 @@ # OpenDroneIdArmStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdArmStatus.msg) ```c diff --git a/docs/en/msg_docs/OpenDroneIdOperatorId.md b/docs/en/msg_docs/OpenDroneIdOperatorId.md index e30192ea9778..cafca0aa0947 100644 --- a/docs/en/msg_docs/OpenDroneIdOperatorId.md +++ b/docs/en/msg_docs/OpenDroneIdOperatorId.md @@ -1,7 +1,5 @@ # OpenDroneIdOperatorId (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdOperatorId.msg) ```c diff --git a/docs/en/msg_docs/OpenDroneIdSelfId.md b/docs/en/msg_docs/OpenDroneIdSelfId.md index e14e7746f4d2..493be28d9fa8 100644 --- a/docs/en/msg_docs/OpenDroneIdSelfId.md +++ b/docs/en/msg_docs/OpenDroneIdSelfId.md @@ -1,7 +1,5 @@ # OpenDroneIdSelfId (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdSelfId.msg) ```c diff --git a/docs/en/msg_docs/OpenDroneIdSystem.md b/docs/en/msg_docs/OpenDroneIdSystem.md index 2fb1943c792d..402b7d0bafd8 100644 --- a/docs/en/msg_docs/OpenDroneIdSystem.md +++ b/docs/en/msg_docs/OpenDroneIdSystem.md @@ -1,7 +1,5 @@ # OpenDroneIdSystem (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OpenDroneIdSystem.msg) ```c diff --git a/docs/en/msg_docs/OrbTest.md b/docs/en/msg_docs/OrbTest.md index d833eb9ba357..3cd2460956d2 100644 --- a/docs/en/msg_docs/OrbTest.md +++ b/docs/en/msg_docs/OrbTest.md @@ -1,7 +1,5 @@ # OrbTest (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTest.msg) ```c diff --git a/docs/en/msg_docs/OrbTestLarge.md b/docs/en/msg_docs/OrbTestLarge.md index 8fb96f757f2c..3298811450cb 100644 --- a/docs/en/msg_docs/OrbTestLarge.md +++ b/docs/en/msg_docs/OrbTestLarge.md @@ -1,7 +1,5 @@ # OrbTestLarge (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTestLarge.msg) ```c diff --git a/docs/en/msg_docs/OrbTestMedium.md b/docs/en/msg_docs/OrbTestMedium.md index a5484401c73a..e4a7bec7c05c 100644 --- a/docs/en/msg_docs/OrbTestMedium.md +++ b/docs/en/msg_docs/OrbTestMedium.md @@ -1,7 +1,5 @@ # OrbTestMedium (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/OrbTestMedium.msg) ```c diff --git a/docs/en/msg_docs/Ping.md b/docs/en/msg_docs/Ping.md index 1d68cebad158..1cb8ac54134b 100644 --- a/docs/en/msg_docs/Ping.md +++ b/docs/en/msg_docs/Ping.md @@ -1,7 +1,5 @@ # Ping (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Ping.msg) ```c diff --git a/docs/en/msg_docs/PositionControllerLandingStatus.md b/docs/en/msg_docs/PositionControllerLandingStatus.md index 0e7ce90a2e90..3e58676dc3fb 100644 --- a/docs/en/msg_docs/PositionControllerLandingStatus.md +++ b/docs/en/msg_docs/PositionControllerLandingStatus.md @@ -1,7 +1,5 @@ # PositionControllerLandingStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionControllerLandingStatus.msg) ```c diff --git a/docs/en/msg_docs/PositionControllerStatus.md b/docs/en/msg_docs/PositionControllerStatus.md index 95f0ec0926a8..2fadf80a9e54 100644 --- a/docs/en/msg_docs/PositionControllerStatus.md +++ b/docs/en/msg_docs/PositionControllerStatus.md @@ -1,7 +1,5 @@ # PositionControllerStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PositionControllerStatus.msg) ```c diff --git a/docs/en/msg_docs/PpsCapture.md b/docs/en/msg_docs/PpsCapture.md index ffe87fd2dc9b..e56614738959 100644 --- a/docs/en/msg_docs/PpsCapture.md +++ b/docs/en/msg_docs/PpsCapture.md @@ -1,7 +1,5 @@ # PpsCapture (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PpsCapture.msg) ```c diff --git a/docs/en/msg_docs/PwmInput.md b/docs/en/msg_docs/PwmInput.md index dbf078955b0a..9389ca3fb1e4 100644 --- a/docs/en/msg_docs/PwmInput.md +++ b/docs/en/msg_docs/PwmInput.md @@ -1,7 +1,5 @@ # PwmInput (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/PwmInput.msg) ```c diff --git a/docs/en/msg_docs/QshellReq.md b/docs/en/msg_docs/QshellReq.md index 99cb82472b70..7f8e38c70193 100644 --- a/docs/en/msg_docs/QshellReq.md +++ b/docs/en/msg_docs/QshellReq.md @@ -1,7 +1,5 @@ # QshellReq (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/QshellReq.msg) ```c diff --git a/docs/en/msg_docs/QshellRetval.md b/docs/en/msg_docs/QshellRetval.md index 53cf5063f9e4..3a27b00e9339 100644 --- a/docs/en/msg_docs/QshellRetval.md +++ b/docs/en/msg_docs/QshellRetval.md @@ -1,7 +1,5 @@ # QshellRetval (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/QshellRetval.msg) ```c diff --git a/docs/en/msg_docs/RadioStatus.md b/docs/en/msg_docs/RadioStatus.md index 64e69beba456..58c320308e3e 100644 --- a/docs/en/msg_docs/RadioStatus.md +++ b/docs/en/msg_docs/RadioStatus.md @@ -1,7 +1,5 @@ # RadioStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RadioStatus.msg) ```c diff --git a/docs/en/msg_docs/RateCtrlStatus.md b/docs/en/msg_docs/RateCtrlStatus.md index 28adaafbbde7..90eaa1208f8f 100644 --- a/docs/en/msg_docs/RateCtrlStatus.md +++ b/docs/en/msg_docs/RateCtrlStatus.md @@ -1,7 +1,5 @@ # RateCtrlStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RateCtrlStatus.msg) ```c diff --git a/docs/en/msg_docs/RcParameterMap.md b/docs/en/msg_docs/RcParameterMap.md index a371149b15be..e1ced1f8d1b7 100644 --- a/docs/en/msg_docs/RcParameterMap.md +++ b/docs/en/msg_docs/RcParameterMap.md @@ -1,7 +1,5 @@ # RcParameterMap (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RcParameterMap.msg) ```c diff --git a/docs/en/msg_docs/Rpm.md b/docs/en/msg_docs/Rpm.md index edf6c37e199b..ff2bf9c82792 100644 --- a/docs/en/msg_docs/Rpm.md +++ b/docs/en/msg_docs/Rpm.md @@ -1,7 +1,5 @@ # Rpm (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/Rpm.msg) ```c diff --git a/docs/en/msg_docs/RtlStatus.md b/docs/en/msg_docs/RtlStatus.md index 299b6f4b1675..e585898e8b37 100644 --- a/docs/en/msg_docs/RtlStatus.md +++ b/docs/en/msg_docs/RtlStatus.md @@ -1,7 +1,5 @@ # RtlStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RtlStatus.msg) ```c diff --git a/docs/en/msg_docs/RtlTimeEstimate.md b/docs/en/msg_docs/RtlTimeEstimate.md index 14dbe315948e..a12f553d7108 100644 --- a/docs/en/msg_docs/RtlTimeEstimate.md +++ b/docs/en/msg_docs/RtlTimeEstimate.md @@ -1,7 +1,5 @@ # RtlTimeEstimate (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/RtlTimeEstimate.msg) ```c diff --git a/docs/en/msg_docs/SensorAccel.md b/docs/en/msg_docs/SensorAccel.md index 50e0c9f24046..7f7ad93e57a5 100644 --- a/docs/en/msg_docs/SensorAccel.md +++ b/docs/en/msg_docs/SensorAccel.md @@ -1,7 +1,5 @@ # SensorAccel (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAccel.msg) ```c diff --git a/docs/en/msg_docs/SensorAccelFifo.md b/docs/en/msg_docs/SensorAccelFifo.md index b624951f0774..86f5a02a06db 100644 --- a/docs/en/msg_docs/SensorAccelFifo.md +++ b/docs/en/msg_docs/SensorAccelFifo.md @@ -1,7 +1,5 @@ # SensorAccelFifo (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAccelFifo.msg) ```c diff --git a/docs/en/msg_docs/SensorAirflow.md b/docs/en/msg_docs/SensorAirflow.md index 72bdd43e2cfb..82b8706060ed 100644 --- a/docs/en/msg_docs/SensorAirflow.md +++ b/docs/en/msg_docs/SensorAirflow.md @@ -1,7 +1,5 @@ # SensorAirflow (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorAirflow.msg) ```c diff --git a/docs/en/msg_docs/SensorGyro.md b/docs/en/msg_docs/SensorGyro.md index d55d2f44c2f5..ee2b4f084aeb 100644 --- a/docs/en/msg_docs/SensorGyro.md +++ b/docs/en/msg_docs/SensorGyro.md @@ -1,7 +1,5 @@ # SensorGyro (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyro.msg) ```c diff --git a/docs/en/msg_docs/SensorGyroFft.md b/docs/en/msg_docs/SensorGyroFft.md index 279c2428aeab..645ce2b2dcbe 100644 --- a/docs/en/msg_docs/SensorGyroFft.md +++ b/docs/en/msg_docs/SensorGyroFft.md @@ -1,7 +1,5 @@ # SensorGyroFft (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyroFft.msg) ```c diff --git a/docs/en/msg_docs/SensorGyroFifo.md b/docs/en/msg_docs/SensorGyroFifo.md index 3de5eff4d848..4d440b1129fd 100644 --- a/docs/en/msg_docs/SensorGyroFifo.md +++ b/docs/en/msg_docs/SensorGyroFifo.md @@ -1,7 +1,5 @@ # SensorGyroFifo (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGyroFifo.msg) ```c diff --git a/docs/en/msg_docs/SensorHygrometer.md b/docs/en/msg_docs/SensorHygrometer.md index 34bedf9ae998..e3da07593f3b 100644 --- a/docs/en/msg_docs/SensorHygrometer.md +++ b/docs/en/msg_docs/SensorHygrometer.md @@ -1,7 +1,5 @@ # SensorHygrometer (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorHygrometer.msg) ```c diff --git a/docs/en/msg_docs/SensorMag.md b/docs/en/msg_docs/SensorMag.md index d574b95e1f06..b3cb27bb11a2 100644 --- a/docs/en/msg_docs/SensorMag.md +++ b/docs/en/msg_docs/SensorMag.md @@ -1,7 +1,5 @@ # SensorMag (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorMag.msg) ```c diff --git a/docs/en/msg_docs/SensorOpticalFlow.md b/docs/en/msg_docs/SensorOpticalFlow.md index d4ea32da3473..b1b131b50dd7 100644 --- a/docs/en/msg_docs/SensorOpticalFlow.md +++ b/docs/en/msg_docs/SensorOpticalFlow.md @@ -1,7 +1,5 @@ # SensorOpticalFlow (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorOpticalFlow.msg) ```c diff --git a/docs/en/msg_docs/SystemPower.md b/docs/en/msg_docs/SystemPower.md index c33cffca779a..eac7503f972b 100644 --- a/docs/en/msg_docs/SystemPower.md +++ b/docs/en/msg_docs/SystemPower.md @@ -1,7 +1,5 @@ # SystemPower (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/SystemPower.msg) ```c diff --git a/docs/en/msg_docs/TecsStatus.md b/docs/en/msg_docs/TecsStatus.md index 96643b3d4458..ce79ad1b7b44 100644 --- a/docs/en/msg_docs/TecsStatus.md +++ b/docs/en/msg_docs/TecsStatus.md @@ -1,7 +1,5 @@ # TecsStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TecsStatus.msg) ```c diff --git a/docs/en/msg_docs/TelemetryStatus.md b/docs/en/msg_docs/TelemetryStatus.md index 87ca267be638..1d12591375a5 100644 --- a/docs/en/msg_docs/TelemetryStatus.md +++ b/docs/en/msg_docs/TelemetryStatus.md @@ -1,7 +1,5 @@ # TelemetryStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TelemetryStatus.msg) ```c diff --git a/docs/en/msg_docs/TiltrotorExtraControls.md b/docs/en/msg_docs/TiltrotorExtraControls.md index 80a1bd7ac1bb..461e16e1a02a 100644 --- a/docs/en/msg_docs/TiltrotorExtraControls.md +++ b/docs/en/msg_docs/TiltrotorExtraControls.md @@ -1,7 +1,5 @@ # TiltrotorExtraControls (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TiltrotorExtraControls.msg) ```c diff --git a/docs/en/msg_docs/TimesyncStatus.md b/docs/en/msg_docs/TimesyncStatus.md index 2488b8c577ce..96ff9258beb2 100644 --- a/docs/en/msg_docs/TimesyncStatus.md +++ b/docs/en/msg_docs/TimesyncStatus.md @@ -1,7 +1,5 @@ # TimesyncStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/TimesyncStatus.msg) ```c diff --git a/docs/en/msg_docs/UnregisterExtComponent.md b/docs/en/msg_docs/UnregisterExtComponent.md index 5a36c8561359..b09ea24d4366 100644 --- a/docs/en/msg_docs/UnregisterExtComponent.md +++ b/docs/en/msg_docs/UnregisterExtComponent.md @@ -1,7 +1,5 @@ # UnregisterExtComponent (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/UnregisterExtComponent.msg) ```c diff --git a/docs/en/msg_docs/VehicleAcceleration.md b/docs/en/msg_docs/VehicleAcceleration.md index 1fb3d0880c3c..ea20cad6a971 100644 --- a/docs/en/msg_docs/VehicleAcceleration.md +++ b/docs/en/msg_docs/VehicleAcceleration.md @@ -1,7 +1,5 @@ # VehicleAcceleration (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAcceleration.msg) ```c diff --git a/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md b/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md index d10cabdb557f..3caa12669ed6 100644 --- a/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md +++ b/docs/en/msg_docs/VehicleAngularAccelerationSetpoint.md @@ -1,7 +1,5 @@ # VehicleAngularAccelerationSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleAngularAccelerationSetpoint.msg) ```c diff --git a/docs/en/msg_docs/VehicleAngularVelocity.md b/docs/en/msg_docs/VehicleAngularVelocity.md index 2c94cb706a1f..fb05ad0f51ab 100644 --- a/docs/en/msg_docs/VehicleAngularVelocity.md +++ b/docs/en/msg_docs/VehicleAngularVelocity.md @@ -1,7 +1,5 @@ # VehicleAngularVelocity (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAngularVelocity.msg) ```c diff --git a/docs/en/msg_docs/VehicleAttitudeSetpoint.md b/docs/en/msg_docs/VehicleAttitudeSetpoint.md index 69552e23efc5..9cd9ba092bf3 100644 --- a/docs/en/msg_docs/VehicleAttitudeSetpoint.md +++ b/docs/en/msg_docs/VehicleAttitudeSetpoint.md @@ -1,7 +1,5 @@ # VehicleAttitudeSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleAttitudeSetpoint.msg) ```c diff --git a/docs/en/msg_docs/VehicleAttitudeSetpointV0.md b/docs/en/msg_docs/VehicleAttitudeSetpointV0.md index 9b3a8c655e9b..6eb03e797cb9 100644 --- a/docs/en/msg_docs/VehicleAttitudeSetpointV0.md +++ b/docs/en/msg_docs/VehicleAttitudeSetpointV0.md @@ -1,7 +1,5 @@ # VehicleAttitudeSetpointV0 (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/px4_msgs_old/msg/VehicleAttitudeSetpointV0.msg) ```c diff --git a/docs/en/msg_docs/VehicleControlMode.md b/docs/en/msg_docs/VehicleControlMode.md index 0c6d062938ee..b32f09c7253e 100644 --- a/docs/en/msg_docs/VehicleControlMode.md +++ b/docs/en/msg_docs/VehicleControlMode.md @@ -1,7 +1,5 @@ # VehicleControlMode (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleControlMode.msg) ```c diff --git a/docs/en/msg_docs/VehicleImuStatus.md b/docs/en/msg_docs/VehicleImuStatus.md index 1d26a7af3657..c6335b8f3b62 100644 --- a/docs/en/msg_docs/VehicleImuStatus.md +++ b/docs/en/msg_docs/VehicleImuStatus.md @@ -1,7 +1,5 @@ # VehicleImuStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleImuStatus.msg) ```c diff --git a/docs/en/msg_docs/VehicleLandDetected.md b/docs/en/msg_docs/VehicleLandDetected.md index bd53ce680f3e..acd95de1909b 100644 --- a/docs/en/msg_docs/VehicleLandDetected.md +++ b/docs/en/msg_docs/VehicleLandDetected.md @@ -1,7 +1,5 @@ # VehicleLandDetected (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleLandDetected.msg) ```c diff --git a/docs/en/msg_docs/VehicleMagnetometer.md b/docs/en/msg_docs/VehicleMagnetometer.md index 3d8f504fd4e6..a847ae520c34 100644 --- a/docs/en/msg_docs/VehicleMagnetometer.md +++ b/docs/en/msg_docs/VehicleMagnetometer.md @@ -1,7 +1,5 @@ # VehicleMagnetometer (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleMagnetometer.msg) ```c diff --git a/docs/en/msg_docs/VehicleOpticalFlowVel.md b/docs/en/msg_docs/VehicleOpticalFlowVel.md index eec61e9ba948..c8dd30792199 100644 --- a/docs/en/msg_docs/VehicleOpticalFlowVel.md +++ b/docs/en/msg_docs/VehicleOpticalFlowVel.md @@ -1,7 +1,5 @@ # VehicleOpticalFlowVel (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleOpticalFlowVel.msg) ```c diff --git a/docs/en/msg_docs/VehicleRatesSetpoint.md b/docs/en/msg_docs/VehicleRatesSetpoint.md index ebc5827d68a7..1281c7409160 100644 --- a/docs/en/msg_docs/VehicleRatesSetpoint.md +++ b/docs/en/msg_docs/VehicleRatesSetpoint.md @@ -1,7 +1,5 @@ # VehicleRatesSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleRatesSetpoint.msg) ```c diff --git a/docs/en/msg_docs/VehicleThrustSetpoint.md b/docs/en/msg_docs/VehicleThrustSetpoint.md index 6bcf6e9d1316..d256e77145eb 100644 --- a/docs/en/msg_docs/VehicleThrustSetpoint.md +++ b/docs/en/msg_docs/VehicleThrustSetpoint.md @@ -1,7 +1,5 @@ # VehicleThrustSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg) ```c diff --git a/docs/en/msg_docs/VehicleTorqueSetpoint.md b/docs/en/msg_docs/VehicleTorqueSetpoint.md index d67e37b3a3d3..2fccc89f4265 100644 --- a/docs/en/msg_docs/VehicleTorqueSetpoint.md +++ b/docs/en/msg_docs/VehicleTorqueSetpoint.md @@ -1,7 +1,5 @@ # VehicleTorqueSetpoint (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg) ```c diff --git a/docs/en/msg_docs/WheelEncoders.md b/docs/en/msg_docs/WheelEncoders.md index 8a10dc11ad79..d91ba6725586 100644 --- a/docs/en/msg_docs/WheelEncoders.md +++ b/docs/en/msg_docs/WheelEncoders.md @@ -1,7 +1,5 @@ # WheelEncoders (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/WheelEncoders.msg) ```c diff --git a/docs/en/msg_docs/YawEstimatorStatus.md b/docs/en/msg_docs/YawEstimatorStatus.md index 888f7628ba94..88bc5614ecb0 100644 --- a/docs/en/msg_docs/YawEstimatorStatus.md +++ b/docs/en/msg_docs/YawEstimatorStatus.md @@ -1,7 +1,5 @@ # YawEstimatorStatus (UORB message) - - [source file](https://github.com/PX4/PX4-Autopilot/blob/main/msg/YawEstimatorStatus.msg) ```c diff --git a/docs/en/msg_docs/index.md b/docs/en/msg_docs/index.md index 359abfc67f2e..e0be504e6d77 100644 --- a/docs/en/msg_docs/index.md +++ b/docs/en/msg_docs/index.md @@ -15,10 +15,10 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [ActuatorMotors](ActuatorMotors.md) — Motor control message - [ActuatorServos](ActuatorServos.md) — Servo control message -- [AirspeedValidated](AirspeedValidated.md) — Validated airspeed -- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply -- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request -- [BatteryStatus](BatteryStatus.md) — Battery status +- [AirspeedValidated](AirspeedValidated.md) +- [ArmingCheckReply](ArmingCheckReply.md) — Arming check reply. +- [ArmingCheckRequest](ArmingCheckRequest.md) — Arming check request. +- [BatteryStatus](BatteryStatus.md) - [ConfigOverrides](ConfigOverrides.md) — Configurable overrides by (external) modes or mode executors - [Event](Event.md) — Events interface - [FixedWingLateralSetpoint](FixedWingLateralSetpoint.md) — Fixed Wing Lateral Setpoint message @@ -70,25 +70,23 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleLandDetected](VehicleLandDetected.md) - [VehicleLocalPosition](VehicleLocalPosition.md) — Fused local position in NED. The coordinate system origin is the vehicle position at the time when the EKF2-module was started. -- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data +- [VehicleOdometry](VehicleOdometry.md) — Vehicle odometry data. Fits ROS REP 147 for aerial vehicles - [VehicleRatesSetpoint](VehicleRatesSetpoint.md) - [VehicleStatus](VehicleStatus.md) — Encodes the system state of the vehicle published by commander - [VtolVehicleStatus](VtolVehicleStatus.md) — VEHICLE_VTOL_STATE, should match 1:1 MAVLinks's MAV_VTOL_STATE -- [Wind](Wind.md) — Wind estimate (from EKF2) ## Unversioned Messages -- [ActionRequest](ActionRequest.md) — Action request for the vehicle's main state +- [ActionRequest](ActionRequest.md) - [ActuatorArmed](ActuatorArmed.md) - [ActuatorControlsStatus](ActuatorControlsStatus.md) - [ActuatorOutputs](ActuatorOutputs.md) - [ActuatorServosTrim](ActuatorServosTrim.md) — Servo trims, added as offset to servo outputs - [ActuatorTest](ActuatorTest.md) -- [AdcReport](AdcReport.md) — ADC raw data. -- [Airspeed](Airspeed.md) — Airspeed data from sensors -- [AirspeedWind](AirspeedWind.md) — Wind estimate (from airspeed_selector) -- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) — Autotune attitude control status -- [BatteryInfo](BatteryInfo.md) — Battery information +- [AdcReport](AdcReport.md) +- [Airspeed](Airspeed.md) +- [AirspeedWind](AirspeedWind.md) +- [AutotuneAttitudeControlStatus](AutotuneAttitudeControlStatus.md) - [ButtonEvent](ButtonEvent.md) - [CameraCapture](CameraCapture.md) - [CameraStatus](CameraStatus.md) @@ -105,11 +103,9 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [DebugKeyValue](DebugKeyValue.md) - [DebugValue](DebugValue.md) - [DebugVect](DebugVect.md) -- [DeviceInformation](DeviceInformation.md) — Device information -- [DifferentialPressure](DifferentialPressure.md) — Differential-pressure (airspeed) sensor +- [DifferentialPressure](DifferentialPressure.md) - [DistanceSensor](DistanceSensor.md) — DISTANCE_SENSOR message data - [DistanceSensorModeChangeRequest](DistanceSensorModeChangeRequest.md) -- [DronecanNodeStatus](DronecanNodeStatus.md) - [Ekf2Timestamps](Ekf2Timestamps.md) — this message contains the (relative) timestamps of the sensor inputs used by EKF2. It can be used for reproducible replay. - [EscReport](EscReport.md) @@ -141,7 +137,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [FollowTargetEstimator](FollowTargetEstimator.md) - [FollowTargetStatus](FollowTargetStatus.md) - [FuelTankStatus](FuelTankStatus.md) -- [GainCompression](GainCompression.md) - [GeneratorStatus](GeneratorStatus.md) - [GeofenceResult](GeofenceResult.md) - [GeofenceStatus](GeofenceStatus.md) @@ -190,7 +185,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [NavigatorMissionItem](NavigatorMissionItem.md) - [NavigatorStatus](NavigatorStatus.md) — Current status of a Navigator mode The possible values of nav_state are defined in the VehicleStatus msg. -- [NeuralControl](NeuralControl.md) — Neural control - [NormalizedUnsignedSetpoint](NormalizedUnsignedSetpoint.md) - [ObstacleDistance](ObstacleDistance.md) — Obstacle distances in front of the sensor. - [OffboardControlMode](OffboardControlMode.md) — Off-board control mode @@ -217,7 +211,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [PowerButtonState](PowerButtonState.md) — power button state notification message - [PowerMonitor](PowerMonitor.md) — power monitor message - [PpsCapture](PpsCapture.md) -- [PurePursuitStatus](PurePursuitStatus.md) — Pure pursuit status +- [PurePursuitStatus](PurePursuitStatus.md) - [PwmInput](PwmInput.md) - [Px4ioStatus](Px4ioStatus.md) - [QshellReq](QshellReq.md) @@ -226,15 +220,15 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [RateCtrlStatus](RateCtrlStatus.md) - [RcChannels](RcChannels.md) - [RcParameterMap](RcParameterMap.md) -- [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md) — Rover Attitude Setpoint -- [RoverAttitudeStatus](RoverAttitudeStatus.md) — Rover Attitude Status -- [RoverPositionSetpoint](RoverPositionSetpoint.md) — Rover Position Setpoint -- [RoverRateSetpoint](RoverRateSetpoint.md) — Rover Rate setpoint -- [RoverRateStatus](RoverRateStatus.md) — Rover Rate Status -- [RoverSpeedSetpoint](RoverSpeedSetpoint.md) — Rover Speed Setpoint -- [RoverSpeedStatus](RoverSpeedStatus.md) — Rover Velocity Status -- [RoverSteeringSetpoint](RoverSteeringSetpoint.md) — Rover Steering setpoint -- [RoverThrottleSetpoint](RoverThrottleSetpoint.md) — Rover Throttle setpoint +- [RoverAttitudeSetpoint](RoverAttitudeSetpoint.md) +- [RoverAttitudeStatus](RoverAttitudeStatus.md) +- [RoverPositionSetpoint](RoverPositionSetpoint.md) +- [RoverRateSetpoint](RoverRateSetpoint.md) +- [RoverRateStatus](RoverRateStatus.md) +- [RoverSteeringSetpoint](RoverSteeringSetpoint.md) +- [RoverThrottleSetpoint](RoverThrottleSetpoint.md) +- [RoverVelocitySetpoint](RoverVelocitySetpoint.md) +- [RoverVelocityStatus](RoverVelocityStatus.md) - [Rpm](Rpm.md) - [RtlStatus](RtlStatus.md) - [RtlTimeEstimate](RtlTimeEstimate.md) @@ -242,13 +236,12 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [SensorAccel](SensorAccel.md) - [SensorAccelFifo](SensorAccelFifo.md) - [SensorAirflow](SensorAirflow.md) -- [SensorBaro](SensorBaro.md) — Barometer sensor +- [SensorBaro](SensorBaro.md) - [SensorCombined](SensorCombined.md) — Sensor readings in SI-unit form. These fields are scaled and offset-compensated where possible and do not change with board revisions and sensor updates. - [SensorCorrection](SensorCorrection.md) — Sensor corrections in SI-unit form for the voted sensor - [SensorGnssRelative](SensorGnssRelative.md) — GNSS relative positioning information in NED frame. The NED frame is defined as the local topological system at the reference station. -- [SensorGnssStatus](SensorGnssStatus.md) — Gnss quality indicators - [SensorGps](SensorGps.md) — GPS position in WGS84 coordinates. the field 'timestamp' is for the position & velocity (microseconds) - [SensorGyro](SensorGyro.md) @@ -261,7 +254,6 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m The topic will not be updated when the vehicle is armed - [SensorSelection](SensorSelection.md) — Sensor ID's for the voted sensors output on the sensor_combined topic. Will be updated on startup of the sensor module and when sensor selection changes -- [SensorTemp](SensorTemp.md) - [SensorUwb](SensorUwb.md) — UWB distance contains the distance information measured by an ultra-wideband positioning system, such as Pozyx or NXP Rddrone. - [SensorsStatus](SensorsStatus.md) — Sensor check metrics. This will be zero for a sensor that's primary or unpopulated. @@ -285,7 +277,7 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [UlogStreamAck](UlogStreamAck.md) — Ack a previously sent ulog_stream message that had the NEED_ACK flag set - [VehicleAcceleration](VehicleAcceleration.md) -- [VehicleAirData](VehicleAirData.md) — Vehicle air data +- [VehicleAirData](VehicleAirData.md) - [VehicleAngularAccelerationSetpoint](VehicleAngularAccelerationSetpoint.md) - [VehicleConstraints](VehicleConstraints.md) — Local setpoint constraints in NED frame setting something to NaN means that no limit is provided @@ -302,18 +294,11 @@ Graphs showing how these are used [can be found here](../middleware/uorb_graph.m - [VehicleTorqueSetpoint](VehicleTorqueSetpoint.md) - [VelocityLimits](VelocityLimits.md) — Velocity and yaw rate limits for a multicopter position slow mode only - [WheelEncoders](WheelEncoders.md) +- [Wind](Wind.md) - [YawEstimatorStatus](YawEstimatorStatus.md) - [AirspeedValidatedV0](AirspeedValidatedV0.md) - [ArmingCheckReplyV0](ArmingCheckReplyV0.md) -- [ArmingCheckRequestV0](ArmingCheckRequestV0.md) — Arming check request. -- [BatteryStatusV0](BatteryStatusV0.md) — Battery status -- [ConfigOverridesV0](ConfigOverridesV0.md) — Configurable overrides by (external) modes or mode executors - [EventV0](EventV0.md) — this message is required here in the msg_old folder because other msg are depending on it Events interface -- [HomePositionV0](HomePositionV0.md) — GPS home position in WGS84 coordinates. -- [RegisterExtComponentReplyV0](RegisterExtComponentReplyV0.md) -- [RegisterExtComponentRequestV0](RegisterExtComponentRequestV0.md) — Request to register an external component - [VehicleAttitudeSetpointV0](VehicleAttitudeSetpointV0.md) -- [VehicleLocalPositionV0](VehicleLocalPositionV0.md) — Fused local position in NED. - The coordinate system origin is the vehicle position at the time when the EKF2-module was started. - [VehicleStatusV0](VehicleStatusV0.md) — Encodes the system state of the vehicle published by commander diff --git a/docs/en/payloads/generic_actuator_control.md b/docs/en/payloads/generic_actuator_control.md index 46b0248bf17a..82bd1f4df93c 100644 --- a/docs/en/payloads/generic_actuator_control.md +++ b/docs/en/payloads/generic_actuator_control.md @@ -56,7 +56,6 @@ To use a generic actuator in a mission: 1. Change the waypoint mission item to a "Set actuator" mission item: ![Set actuator mission item](../../assets/qgc/plan/mission_item_editors/mission_item_select_set_actuator.png) - - Select the header on the waypoint mission editor to open the **Select Mission Command** editor. - Select the category **Advanced**, and then the **Set actuator** item (if the item is not present, try a more recent version of _QGroundControl_ or a daily build). This will change the mission item type to "Set actuator". diff --git a/docs/en/peripherals/gripper.md b/docs/en/peripherals/gripper.md index 07886d70caa9..da62f315d2d0 100644 --- a/docs/en/peripherals/gripper.md +++ b/docs/en/peripherals/gripper.md @@ -72,7 +72,6 @@ To set the actuation timeout: There are two easy ways to open and close the gripper. While the drone is on a bench and the propellers are removed: - - Run the `payload_deliverer` test in the QGC [MAVLink Shell](../debug/mavlink_shell.md): ```sh diff --git a/docs/en/peripherals/mavlink_peripherals.md b/docs/en/peripherals/mavlink_peripherals.md index 111d723ffd45..9a790a9218d3 100644 --- a/docs/en/peripherals/mavlink_peripherals.md +++ b/docs/en/peripherals/mavlink_peripherals.md @@ -28,7 +28,6 @@ The parameters for each instance are: For more information see [Serial Port Configuration](../peripherals/serial_configuration.md). - [MAV_X_MODE](../advanced_config/parameter_reference.md#MAV_0_MODE) - Specify the telemetry mode/target (the set of messages to stream for the current instance and their rate). The default values are: - - _Normal_: Standard set of messages for a GCS. - _Custom_ or _Magic_: Nothing (in the default PX4 implementation). Modes may be used for testing when developing a new mode. diff --git a/docs/en/peripherals/remote_id.md b/docs/en/peripherals/remote_id.md index 399b2cf973f8..60d3413661f4 100644 --- a/docs/en/peripherals/remote_id.md +++ b/docs/en/peripherals/remote_id.md @@ -165,7 +165,6 @@ PX4 v1.14 streams these messages by default (in streaming modes: normal, onboard - [OPEN_DRONE_ID_LOCATION](https://mavlink.io/en/messages/common.html#OPEN_DRONE_ID_LOCATION) (1 Hz) - UAV location, altitude, direction, and speed. - [OPEN_DRONE_ID_SYSTEM](https://mavlink.io/en/messages/common.html#OPEN_DRONE_ID_SYSTEM) (1 Hz) Operator location/altitude, multiple aircraft information (group/swarm, if applicable), full timestamp and possible category/class information. - - Implementation assumes operator is located at vehicle home position (does not yet support getting operator position from GCS). This is believed to be compliant for broadcast-only Remote IDs. @@ -243,7 +242,7 @@ If the Remote ID CAN node is present and the messages are not being received, th 2. Navigate to the [Application settings](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/settings_view/general.html): **Application Settings > General > Miscellaneous**. 3. Select `Enable Remote ID`. The Remote ID tab should appear. - + ::: info If this option is not present you may be in a very recent version of QGC. In that case, open the view at: **Application Settings > Remote ID**. diff --git a/docs/en/peripherals/serial_configuration.md b/docs/en/peripherals/serial_configuration.md index 9228a0ad5af0..65650feef510 100644 --- a/docs/en/peripherals/serial_configuration.md +++ b/docs/en/peripherals/serial_configuration.md @@ -106,7 +106,6 @@ The following ports are commonly mapped to specific functions on all boards: This is configured by default as a MAVLink port the onboard profile (for companion computers). The configuration for MAVLink is unique to this port (it doesn't use the `MAV_X_CONFIG` parameters). - - [SYS_USB_AUTO](../advanced_config/parameter_reference.md#SYS_USB_AUTO) sets whether the port is set to no partiular protocol, autodetects the protocol, or sets the comms link to MAVLink. - [USB_MAV_MODE](../advanced_config/parameter_reference.md#USB_MAV_MODE) sets the MAVLink profile that is used if MAVLink is set or detected. diff --git a/docs/en/power_module/ark_12s_pab_power_module.md b/docs/en/power_module/ark_12s_pab_power_module.md index 77c33cf32e0d..63c6223758cf 100644 --- a/docs/en/power_module/ark_12s_pab_power_module.md +++ b/docs/en/power_module/ark_12s_pab_power_module.md @@ -13,25 +13,21 @@ Order this module from: ## Hardware Specifications - **TI INA238 Digital Power Monitor** - - 0.0001 Ohm Shunt - I2C Interface - **5.2V 6A Step-Down Regulator** - - 66V Maximum Input Voltage - 10V Minimum Input Voltage at 6A Out - Output Over-Current Protection - **Connections** - - Solder Pads Battery Input - Solder Pads Battery Output - 6 Pin Molex CLIK-Mate Output - [Matches ARK PAB Carrier Power Pinout](https://arkelectron.gitbook.io/ark-documentation/flight-controllers/ark-pixhawk-autopilot-bus-carrier/pinout) - **Other** - - USA Built - Includes 6 Pin Molex CLIK-Mate Cable diff --git a/docs/en/power_module/cuav_hv_pm.md b/docs/en/power_module/cuav_hv_pm.md index 7093c588ed9c..48e169a7f873 100644 --- a/docs/en/power_module/cuav_hv_pm.md +++ b/docs/en/power_module/cuav_hv_pm.md @@ -1,9 +1,9 @@ # CUAV HV PM (High-Voltage Power Module) -The CUAV® *HV_PM* power module is a "high voltage" power module independently developed by CUAV. +The CUAV® _HV_PM_ power module is a "high voltage" power module independently developed by CUAV. :::tip -The *HV_PM* is included in the CUAV V5+/V5 nano kit, but is also be sold separately. +The _HV_PM_ is included in the CUAV V5+/V5 nano kit, but is also be sold separately. There are different cables depending on the flight controller (Pixhack v3, V5+/V5 nano, Pixhawk). It can be used with other flight controllers, but you may need to modify the cable pin. ::: @@ -12,7 +12,7 @@ It can be used with other flight controllers, but you may need to modify the cab - **Higher voltage input:** 10V-60V (3s~14s battery) - **Accurate battery monitor:** - - **Voltage detection accuracy:** +-0.1v; + - **Voltage detection accuracy:** +-0.1v; - **Current detection accuracy:** +-0.2A - **BEC (5v) max current:** 5A - **Max (detection) current:** 60A @@ -31,5 +31,6 @@ It can be used with other flight controllers, but you may need to modify the cab [Battery Estimation Tuning](../config/battery.md) describes how to configure the battery and power module. The key configuration settings for `HV_PM` are: + - **Voltage divider:** 18 - **Amps per volt:** 24 A/V diff --git a/docs/en/power_module/holybro_pm02.md b/docs/en/power_module/holybro_pm02.md index 0f88cabf2099..adb6447710ad 100644 --- a/docs/en/power_module/holybro_pm02.md +++ b/docs/en/power_module/holybro_pm02.md @@ -9,7 +9,6 @@ The module can be used with other flight controllers that require an analog powe ![Holybro PM02](../../assets/hardware/power_module/holybro_pm02/pm02.jpg) - ## Specifications - **Rated current**: 60A diff --git a/docs/en/power_module/holybro_pm03d.md b/docs/en/power_module/holybro_pm03d.md index 7f6825a0c272..526beebf6915 100644 --- a/docs/en/power_module/holybro_pm03d.md +++ b/docs/en/power_module/holybro_pm03d.md @@ -31,13 +31,13 @@ The PM is **NOT** compatible with flight controllers that require an analog powe - **Mounting**: 45 x 45mm - **Weight**: 59g - **Connections**: - - XT-60 for battery - - XT-30 for motor & peripheral device (battery voltage) - - Solder pads in each corner (battery voltage) - - CLIK-Mate 2.0mm for flight controller (5.2V/3A standalone BEC) - - JST GH 4pin (5.2V/3A, BEC shared with 5.2V triple row pin header) - - 2x Triple row pin header (5.2V/3A, BEC shared with JST GH 4pin) - - 2x Triple row pin header (8V or 12V selectable by moving header jumper, 3A) +- XT-60 for battery +- XT-30 for motor & peripheral device (battery voltage) +- Solder pads in each corner (battery voltage) +- CLIK-Mate 2.0mm for flight controller (5.2V/3A standalone BEC) +- JST GH 4pin (5.2V/3A, BEC shared with 5.2V triple row pin header) +- 2x Triple row pin header (5.2V/3A, BEC shared with JST GH 4pin) +- 2x Triple row pin header (8V or 12V selectable by moving header jumper, 3A) ## Package Contents @@ -46,8 +46,8 @@ The PM is **NOT** compatible with flight controllers that require an analog powe - 1x Electrolytic capacitor: 220uF 63V (pre-soldered) - 1x 2.0mm pitch CLIK-Mate 6pin cable (To power flight controller) - 4pin JST GH to USB Type C -- 4pin JST GH to barrel plug (2.1*5.5mm) -- 4pin JST GH to barrel plug (2.5*5.5mm) +- 4pin JST GH to barrel plug (2.1\*5.5mm) +- 4pin JST GH to barrel plug (2.5\*5.5mm) - 4pin Pin Dupont Cable (2pc) - Nylon standoffs & nuts diff --git a/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md b/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md index ea8ac4f99a08..9821c35cea15 100644 --- a/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md +++ b/docs/en/power_module/holybro_pm06_pixhawk4mini_power_module.md @@ -4,7 +4,6 @@ This power module has integrated power distribution board and provides regulated ![PM06](../../assets/hardware/power_module/holybro_pm06_14s/pm06v2_pm06v2-14s.jpg) - ## Specifications - **PCB Current:** 120A continued @@ -18,7 +17,7 @@ This power module has integrated power distribution board and provides regulated ## Mechanical Specifications - **Dimensions:** 35x35x5mm -- **Mounting hole:** 30.5mm*30.5mm +- **Mounting hole:** 30.5mm\*30.5mm - **Weight:** 24g ## Where to Buy diff --git a/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md b/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md index a1791ff1776e..0e7f7414fed8 100644 --- a/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md +++ b/docs/en/power_module/holybro_pm07_pixhawk4_power_module.md @@ -33,14 +33,12 @@ This module can be purchased as bundle with [Pixhawk 4](../assembly/quick_start_ [Pixhawk 4 Power Module (PM07)](https://holybro.com/collections/power-modules-pdbs/products/pixhawk-4-power-module-pm07) - ## Wiring/Connections Wiring and connection information can be found in: [Pixhawk 4 > Power](../assembly/quick_start_pixhawk4.md#power). ![Pixhawk 4 - Power Management Board](../../assets/hardware/power_module/holybro_pm07/pixhawk4_power_management_board.png) - ## Further Information [Quick Start Guide](https://docs.holybro.com/power-module-and-pdb/power-module/pm07-quick-start-guide) (Holybro) diff --git a/docs/en/power_module/sky-drones_smartap-pdb.md b/docs/en/power_module/sky-drones_smartap-pdb.md index 6447feff24e9..3ea985b7b476 100644 --- a/docs/en/power_module/sky-drones_smartap-pdb.md +++ b/docs/en/power_module/sky-drones_smartap-pdb.md @@ -21,7 +21,6 @@ SmartAP PDB makes connecting high-power lines easier and much more reliable. - Integrated electromagnetic sounder (buzzer) - Power output for the flight controller (both 5V regulated and battery voltage level output) - ## Size and Weight - Length: 65mm @@ -38,12 +37,10 @@ The key configuration settings are: - Voltage divider: 15.51 - Amps per volt: 36.00 - ## Where to buy [SmartAP PDB](https://sky-drones.com/parts/smartap-pdb.html) - ## Wiring / Pinout SmartAP Power Distribution Board pinout diagram is shown below. @@ -61,7 +58,6 @@ The current sensor is located on the bottom side of the PDB. ![SmartAP PDB](../../assets/hardware/power_module/sky-drones_smartap-pdb/smartap-pdb-current-sensor.png) - ## Further Information - [Buy SmartAP PDB](https://sky-drones.com/power/smartap-pdb.html) diff --git a/docs/en/releases/1.13.md b/docs/en/releases/1.13.md index fdda97c87fcc..7357fe68cde0 100644 --- a/docs/en/releases/1.13.md +++ b/docs/en/releases/1.13.md @@ -24,7 +24,6 @@ ### Common - **Explicit Joystick source selection ([PR#17404](https://github.com/PX4/PX4-Autopilot/pull/17404))** - - Possibility to: - Explicitly allow just one source - Fall back to other source in air diff --git a/docs/en/ros/mavros_custom_messages.md b/docs/en/ros/mavros_custom_messages.md index 5f18636ad61c..3549abea35f3 100644 --- a/docs/en/ros/mavros_custom_messages.md +++ b/docs/en/ros/mavros_custom_messages.md @@ -2,6 +2,7 @@ :::warning This article has been tested against: + - **Ubuntu:** 20.04 - **ROS:** Noetic - **PX4 Firmware:** v1.13 @@ -13,13 +14,14 @@ However these steps are fairly general and so it should work with other distros/ ## MAVROS Installation -Follow *Source Installation* instructions from [mavlink/mavros](https://github.com/mavlink/mavros/blob/master/mavros/index.md) to install "ROS Kinetic". +Follow _Source Installation_ instructions from [mavlink/mavros](https://github.com/mavlink/mavros/blob/master/mavros/index.md) to install "ROS Kinetic". ## MAVROS 1. We start by creating a new MAVROS plugin, in this example named **keyboard_command.cpp** (in **workspace/src/mavros/mavros_extras/src/plugins**) by using the code below: The code subscribes a 'char' message from ROS topic `/mavros/keyboard_command/keyboard_sub` and sends it as a MAVLink message. + ```c #include #include @@ -66,6 +68,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ``` 1. Edit **mavros_plugins.xml** (in **workspace/src/mavros/mavros_extras**) and add the following lines: + ```xml Accepts keyboard command. @@ -73,10 +76,11 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ``` 1. Edit **CMakeLists.txt** (in **workspace/src/mavros/mavros_extras**) and add the following line in `add_library`. + ```cmake - add_library( + add_library( ... - src/plugins/keyboard_command.cpp + src/plugins/keyboard_command.cpp ) ``` @@ -93,6 +97,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ## PX4 Changes 1. Inside **common.xml** (in **PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0**), add your MAVLink message as following (same procedure as for MAVROS section above): + ```xml ... @@ -106,10 +111,11 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c Make sure that the **common.xml** files in the following directories are exactly the same: - `PX4-Autopilot/src/modules/mavlink/mavlink/message_definitions/v1.0` - `workspace/src/mavlink/message_definitions/v1.0` - are exactly the same. - ::: + are exactly the same. + ::: 1. Make your own uORB message file **key_command.msg** in (PX4-Autopilot/msg). For this example the "key_command.msg" has only the code: + ``` uint64 timestamp # time since system start (microseconds) char cmd @@ -142,6 +148,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c 1. Edit **mavlink_receiver.cpp** (in **PX4-Autopilot/src/modules/mavlink**). This is where PX4 receives the MAVLink message sent from ROS, and publishes it as a uORB topic. + ```cpp ... void MavlinkReceiver::handle_message(mavlink_message_t *msg) @@ -221,7 +228,7 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c int error_counter = 0; - for (int i = 0; i < 10; i++) + for (int i = 0; i < 10; i++) { int poll_ret = px4_poll(fds, 1, 1000); @@ -258,10 +265,10 @@ Follow *Source Installation* instructions from [mavlink/mavros](https://github.c ``` menuconfig MODULES_KEY_RECEIVER - bool "key_receiver" - default n - ---help--- - Enable support for key_receiver + bool "key_receiver" + default n + ---help--- + Enable support for key_receiver ``` @@ -283,7 +290,7 @@ Now you are ready to build all your work! ### Build for ROS 1. In your workspace enter: `catkin build`. -1. Beforehand, you have to set your "px4.launch" in (/workspace/src/mavros/mavros/launch). +1. Beforehand, you have to set your "px4.launch" in (/workspace/src/mavros/mavros/launch). Edit "px4.launch" as below. If you are using USB to connect your computer with Pixhawk, you have to set "fcu_url" as shown below. But, if you are using CP2102 to connect your computer with Pixhawk, you have to replace "ttyACM0" with "ttyUSB0". @@ -301,22 +308,25 @@ Now you are ready to build all your work! ### Build for PX4 1. Clean the previously built PX4-Autopilot directory. In the root of **PX4-Autopilot** directory: - ```sh - make clean - ``` - -1. Build PX4-Autopilot and upload [in the normal way](../dev_setup/building_px4.md#nuttx-pixhawk-based-boards). - - For example: - - - to build for Pixhawk 4/FMUv5 execute the following command in the root of the PX4-Autopilot directory: - ```sh - make px4_fmu-v5_default upload - ``` - - to build for SITL execute the following command in the root of the PX4-Autopilot directory (using jmavsim simulation): - ```sh - make px4_sitl jmavsim - ``` + + ```sh + make clean + ``` + +1. Build PX4-Autopilot and upload [in the normal way](../dev_setup/building_px4.md#nuttx-pixhawk-based-boards). + + For example: + - to build for Pixhawk 4/FMUv5 execute the following command in the root of the PX4-Autopilot directory: + + ```sh + make px4_fmu-v5_default upload + ``` + + - to build for SITL execute the following command in the root of the PX4-Autopilot directory (using jmavsim simulation): + + ```sh + make px4_sitl jmavsim + ``` ## Running the Code @@ -338,6 +348,7 @@ Next test if the MAVROS message is sent to PX4. 1. Enter the Pixhawk nutshell through UDP. Replace xxx.xx.xxx.xxx with your IP. + ```sh cd PX4-Autopilot/Tools ./mavlink_shell.py xxx.xx.xxx.xxx:14557 --baudrate 57600 diff --git a/docs/en/ros2/multi_vehicle.md b/docs/en/ros2/multi_vehicle.md index e295d49932c7..abed4ee206ed 100644 --- a/docs/en/ros2/multi_vehicle.md +++ b/docs/en/ros2/multi_vehicle.md @@ -38,12 +38,12 @@ This mismatch can be fixed by manually using `PX4_UXRCE_DDS_NS` on the first ins The default client configuration in simulation is summarized as follows: -| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | -|-------------------|----------------|------------------|-----------------------| -| not provided | 0 | `px4_instance+1` | none | -| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | -| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` | -| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| `PX4_UXRCE_DDS_NS` | `px4_instance` | `UXRCE_DDS_KEY` | client namespace | +| ------------------ | -------------- | ---------------- | --------------------- | +| not provided | 0 | `px4_instance+1` | none | +| provided | 0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | +| not provided | >0 | `px4_instance+1` | `px4_${px4_instance}` | +| provided | >0 | `px4_instance+1` | `PX4_UXRCE_DDS_NS` | ## Adjusting the `target_system` value diff --git a/docs/en/ros2/px4_ros2_msg_translation_node.md b/docs/en/ros2/px4_ros2_msg_translation_node.md index f9dab8a42a72..5587c4fdbb15 100644 --- a/docs/en/ros2/px4_ros2_msg_translation_node.md +++ b/docs/en/ros2/px4_ros2_msg_translation_node.md @@ -305,7 +305,6 @@ The example describes the process of updating the `VehicleAttitude` message defi Update the existing translations header files `msg/translation_node/translations/*.h` to reference the newly archived message definition. For example, update references in those files:
- - Replace `px4_msgs::msg::VehicleAttitude` → `px4_msgs_old::msg::VehicleAttitudeV3` - Replace `#include ` → `#include ` @@ -386,7 +385,6 @@ The example describes the process of updating the `VehicleAttitude` message defi ``` Version translation templates are provided here: - - [Direct Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_direct_v1.h) - [Generic Topic Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_multi_v2.h) - [Direct Service Message Translation Template](https://github.com/PX4/PX4-Autopilot/blob/main/msg/translation_node/translations/example_translation_service_v1.h) @@ -440,7 +438,7 @@ For translations with multiple input topics, the translation continues once all - Services messages only support a linear history, i.e. no message splitting or merging. - Having both publishers and subscribers for two different versions of the same topic is currently not handled by the translation node and would trigger infinite circular publications. This refers to the following problematic configuration: - + ``` app 1: pub topic_v1, sub topic_v1 app 2: pub topic_v2, sub topic_v2 diff --git a/docs/en/sensor/inertiallabs.md b/docs/en/sensor/inertiallabs.md index c86ab79e64c3..2d677e0d5369 100644 --- a/docs/en/sensor/inertiallabs.md +++ b/docs/en/sensor/inertiallabs.md @@ -5,7 +5,6 @@ A universal protocol is used for [all Inertial Labs sensors](https://inertiallab ![INS-U](../../assets/hardware/sensors/inertial/ilabs-ins-u.png) - Benefits to PX4 users: - Higher accuracy heading, pitch, and roll estimates diff --git a/docs/en/sensor/microstrain.md b/docs/en/sensor/microstrain.md index c4aad808ebac..9a6964180d16 100644 --- a/docs/en/sensor/microstrain.md +++ b/docs/en/sensor/microstrain.md @@ -40,14 +40,11 @@ To use the MicroStrain driver: 1. Include the module in firmware in the [kconfig board configuration](../hardware/porting_guide_config.md#px4-board-configuration-kconfig) by setting the kconfig variables: `CONFIG_DRIVERS_INS_MICROSTRAIN` or `CONFIG_COMMON_INS`. 2. Configure the driver mode by setting [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) - - To use the MicroStrain sensor to provide raw IMU data to EKF2 - 1. Set [MS_MODE](../advanced_config/parameter_reference.md#MS_MODE) to 0 2. Update the [EKF2_MULTI_IMU](../advanced_config/parameter_reference.md#EKF2_MULTI_IMU) parameter to account for the added MicroStrain sensor. 3. Enable EKF2 by setting [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN) to 1 4. To prioritize MicroStrain sensor output, adjust the priority level of individual sensors from 0-100 using the following parameters: - - [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO) - [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO) - [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO) @@ -57,7 +54,6 @@ To use the MicroStrain driver: ::: tip Sensors can be identified by their device id, which can be found by checking the parameters: - - [CAL_ACCn_ID](../advanced_config/parameter_reference.md#CAL_ACC0_ID) - [CAL_GYROn_ID](../advanced_config/parameter_reference.md#CAL_GYRO0_ID) - [CAL_MAGn_ID](../advanced_config/parameter_reference.md#CAL_MAG0_ID) @@ -76,32 +72,26 @@ To use the MicroStrain driver: ## MicroStrain Configuration 1. Rates: - - By default, accel and gyro data are published at 500 Hz, magnetometer at 50 Hz, and barometric pressure at 50 Hz. This can be changed by adjusting the following parameters: - - [MS_IMU_RATE_HZ](../advanced_config/parameter_reference.md#MS_IMU_RATE_HZ) - [MS_MAG_RATE_HZ](../advanced_config/parameter_reference.md#MS_MAG_RATE_HZ) - [MS_BARO_RATE_HZ](../advanced_config/parameter_reference.md#MS_BARO_RATE_HZ) - Global position, local position, attitude and odometry will be published at 250 Hz by default. This can be configured via: - - [MS_FILT_RATE_HZ](../advanced_config/parameter_reference.md#MS_FILT_RATE_HZ) - For the CV7-GNSS/INS, the GNSS receiver 1 and 2 will publish data at 5Hz by default. This can be changed using: - - [MS_GNSS_RATE_HZ](../advanced_config/parameter_reference.md#MS_GNSS_RATE_HZ) - The driver will automatically configure data outputs based on the specific sensor model and available data streams. - The driver is scheduled to run at twice the fastest configured data rate. 2. Aiding measurements: - - If supported, GNSS position and velocity aiding are always enabled. - Internal/external magnetometer and heading aiding, as well as optical flow aiding, are disabled by default. They can be enabled using the following parameters: - - [MS_INT_MAG_EN](../advanced_config/parameter_reference.md#MS_INT_MAG_EN) - [MS_INT_HEAD_EN](../advanced_config/parameter_reference.md#MS_INT_HEAD_EN) - [MS_EXT_HEAD_EN](../advanced_config/parameter_reference.md#MS_EXT_HEAD_EN) @@ -109,7 +99,6 @@ To use the MicroStrain driver: - [MS_OPT_FLOW_EN](../advanced_config/parameter_reference.md#MS_OPT_FLOW_EN) - The aiding frames for external sources can be configured using the following parameters: - - [MS_EHEAD_YAW](../advanced_config/parameter_reference.md#MS_EHEAD_YAW) - [MS_EMAG_ROLL](../advanced_config/parameter_reference.md#MS_EMAG_ROLL) - [MS_EMAG_PTCH](../advanced_config/parameter_reference.md#MS_EMAG_PTCH) @@ -120,7 +109,6 @@ To use the MicroStrain driver: - [SENS_FLOW_ROT](../advanced_config/parameter_reference.md#SENS_FLOW_ROT) - The uncertainty for optical flow and external magnetometer aiding must be specified using the following parameters: - - [MS_EMAG_UNCERT](../advanced_config/parameter_reference.md#MS_EMAG_UNCERT) - [MS_OFLW_UNCERT](../advanced_config/parameter_reference.md#MS_OFLW_UNCERT) @@ -131,33 +119,24 @@ To use the MicroStrain driver: ::: 3. Initial heading alignment: - - Initial heading alignment is set to kinematic by default. This can be changed by adjusting - - [MS_ALIGNMENT](../advanced_config/parameter_reference.md#MS_ALIGNMENT) 4. GNSS Aiding Source Control (GNSS/INS only) - - The Source of the GNSS aiding data can be configured using: - - [MS_GNSS_AID_SRC](../advanced_config/parameter_reference.md#MS_GNSS_AID_SRC) 5. Sensor to vehicle transform: - - If the sensor is mounted in an orientation different from the vehicle frame. A sensor to vehicle transform can be enabled using - - [MS_SVT_EN](../advanced_config/parameter_reference.md#MS_SVT_EN) - The transform is defined using the following parameters - - [MS_SENSOR_ROLL](../advanced_config/parameter_reference.md#MS_SENSOR_ROLL) - [MS_SENSOR_PTCH](../advanced_config/parameter_reference.md#MS_SENSOR_PTCH) - [MS_SENSOR_YAW](../advanced_config/parameter_reference.md#MS_SENSOR_YAW) 6. IMU ranges: - - The accelerometer and gyroscope ranges on the device are configurable using: - - [MS_ACCEL_RANGE](../advanced_config/parameter_reference.md#MS_ACCEL_RANGE) - [MS_GYRO_RANGE](../advanced_config/parameter_reference.md#MS_GYRO_RANGE) @@ -168,15 +147,12 @@ To use the MicroStrain driver: ::: 7. GNSS Lever arm offsets: - - The lever arm offset for the external GNSS receiver can be configured using: - - [MS_GNSS_OFF1_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_X) - [MS_GNSS_OFF1_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Y) - [MS_GNSS_OFF1_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF1_Z) - For dual-antenna configurations, the second GNSS receiver’s offset is configured using: - - [MS_GNSS_OFF2_X](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_X) - [MS_GNSS_OFF2_Y](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Y) - [MS_GNSS_OFF2_Z](../advanced_config/parameter_reference.md#MS_GNSS_OFF2_Z) diff --git a/docs/en/sensor/optical_flow.md b/docs/en/sensor/optical_flow.md index f4fa4fcf0c99..f76a40b4bbe2 100644 --- a/docs/en/sensor/optical_flow.md +++ b/docs/en/sensor/optical_flow.md @@ -55,7 +55,7 @@ Reducing the optical flow scale factor can improve the situation. It has a PAW3902 optical flow sensor, Broadcom AFBR-S50LV85D 30 meter distance sensor, and Invensense ICM-42688-P 6-Axis IMU. [ARK Flow MR](../dronecan/ark_flow_mr.md) is a [DroneCAN](../dronecan/index.md) optical flow sensor, [distance sensor](../sensor/rangefinders.md), and IMU, for mid-range applications. -It has a PixArt PAA3905 optical flow sensor, Broadcom AFBR-S50LX85D 50 meter distance sensor, and Invensense IIM-42653 6-Axis IMU. +It has a PixArt PAA3905 optical flow sensor, Broadcom AFBR-S50LX85D 50 meter distance sensor, and Invensense IIM-42653 6-Axis IMU. ### Holybro H-Flow diff --git a/docs/en/sensor/sbgecom.md b/docs/en/sensor/sbgecom.md index 508024bbd0a2..2115f1f4c1ca 100644 --- a/docs/en/sensor/sbgecom.md +++ b/docs/en/sensor/sbgecom.md @@ -76,8 +76,7 @@ To use the sbgECom driver: In this case, MAVLink messages will be updated with the newly selected sensor. If you don't want to have this fallback mechanism, you must disable unwanted sensors. - ::: - 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). + ::: 4. If using the sbgECom as an INS, disable EKF2 using [EKF2_EN](../advanced_config/parameter_reference.md#EKF2_EN). 6. Restart PX4. diff --git a/docs/en/sensor/vectornav.md b/docs/en/sensor/vectornav.md index b6291f4e4ee1..cbe8f7b53a1c 100644 --- a/docs/en/sensor/vectornav.md +++ b/docs/en/sensor/vectornav.md @@ -55,11 +55,9 @@ To use the VectorNav driver: 1. Disable magnetometer preflight checks by setting [SYS_HAS_MAG](../advanced_config/parameter_reference.md#SYS_HAS_MAG) to `0`. 1. Allow the VectorNav driver to initialize by restarting PX4. 1. Configure driver as either an external INS or to provide raw data: - - If using the VectorNav as an external INS, set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `INS`. This disables EKF2. - If using the VectorNav as external inertial sensors: - 1. Set [VN_MODE](../advanced_config/parameter_reference.md#VN_MODE) to `Sensors Only` 1. If internal sensors are enabled, prioritize VectorNav sensors using [CAL_GYROn_PRIO](../advanced_config/parameter_reference.md#CAL_GYRO0_PRIO), [CAL_ACCn_PRIO](../advanced_config/parameter_reference.md#CAL_ACC0_PRIO), [CAL_BAROn_PRIO](../advanced_config/parameter_reference.md#CAL_BARO0_PRIO), [CAL_MAGn_PRIO](../advanced_config/parameter_reference.md#CAL_MAG0_PRIO), where _n_ is the instance number of the IMU component (0, 1, etc.). diff --git a/docs/en/sensor_bus/i2c_development.md b/docs/en/sensor_bus/i2c_development.md index b1ddfa21bf46..0a0ccf07e7ef 100644 --- a/docs/en/sensor_bus/i2c_development.md +++ b/docs/en/sensor_bus/i2c_development.md @@ -4,9 +4,10 @@ I2C is a packet-switched serial communication protocol that allows multiple mast It is intended for attaching lower-speed peripheral ICs to processors and microcontrollers in short-distance, intra-board communication. Pixhawk/PX4 support it for: -* Connecting off board components that require higher data rates than provided by a strict serial UART, such as rangefinders. -* Compatibility with peripheral devices that only support I2C. -* Allowing multiple devices to attach to a single bus (useful for conserving ports). + +- Connecting off board components that require higher data rates than provided by a strict serial UART, such as rangefinders. +- Compatibility with peripheral devices that only support I2C. +- Allowing multiple devices to attach to a single bus (useful for conserving ports). For example, LEDs, Compass, rangefinders etc. ::: info @@ -22,15 +23,17 @@ The bus is not fast enough even with a single device attached to allow vibration Drivers should `#include ` and then provide an implementation of the abstract base class `I2C` defined in **I2C.hpp** for the target hardware (i.e. for NuttX [here](https://github.com/PX4/PX4-Autopilot/blob/main/src/lib/drivers/device/nuttx/I2C.hpp)). -A small number of drivers will also need to include headers for their type of device (**drv_*.h**) in [/src/drivers/](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers) - e.g. [drv_led.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/drv_led.h). +A small number of drivers will also need to include headers for their type of device (**drv\_\*.h**) in [/src/drivers/](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers) - e.g. [drv_led.h](https://github.com/PX4/PX4-Autopilot/blob/main/src/drivers/drv_led.h). To include a driver in firmware you must add the driver to the board-specific cmake file that corresponds to the target you want to build for. You can do this for a single driver: + ``` CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y ``` You can also include all drivers of a particular type. + ``` CONFIG_COMMON_DISTANCE_SENSOR=y ``` @@ -44,12 +47,13 @@ For example, you can see/search for `CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LA To find I2C driver examples, search for **i2c.h** in [/src/drivers/](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers). Just a few examples are: -* [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_i2c) - I2C driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). -* [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_serial) - Serial driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). -* [drivers/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - I2C Driver for the MS5611 and MS6507 barometric pressure sensor connected via I2C (or SPI). + +- [drivers/distance_sensor/lightware_laser_i2c](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_i2c) - I2C driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). +- [drivers/distance_sensor/lightware_laser_serial](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/distance_sensor/lightware_laser_serial) - Serial driver for [Lightware SF1XX LIDAR](../sensor/sfxx_lidar.md). +- [drivers/ms5611](https://github.com/PX4/PX4-Autopilot/tree/main/src/drivers/barometer/ms5611) - I2C Driver for the MS5611 and MS6507 barometric pressure sensor connected via I2C (or SPI). ## Further Information -* [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) -* [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) -* [Driver Framework](../middleware/drivers.md) +- [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) +- [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) +- [Driver Framework](../middleware/drivers.md) diff --git a/docs/en/sensor_bus/i2c_general.md b/docs/en/sensor_bus/i2c_general.md index 2715b604e3f8..9242b7c70bf6 100644 --- a/docs/en/sensor_bus/i2c_general.md +++ b/docs/en/sensor_bus/i2c_general.md @@ -4,9 +4,9 @@ It is recommended for: -* Connecting offboard components that require low bandwidth and low latency communication, e.g. [rangefinders](../sensor/rangefinders.md), [magnetometers](../gps_compass/magnetometer.md), [airspeed sensors](../sensor/airspeed.md) and [tachometers](../sensor/tachometers.md). -* Compatibility with peripheral devices that only support I2C. -* Allowing multiple devices to attach to a single bus, which is useful for conserving ports. +- Connecting offboard components that require low bandwidth and low latency communication, e.g. [rangefinders](../sensor/rangefinders.md), [magnetometers](../gps_compass/magnetometer.md), [airspeed sensors](../sensor/airspeed.md) and [tachometers](../sensor/tachometers.md). +- Compatibility with peripheral devices that only support I2C. +- Allowing multiple devices to attach to a single bus, which is useful for conserving ports. I2C allows multiple master devices to connect to multiple slave devices using only 2 wires per connection (SDA, SCL). in theory, a bus can support 128 devices, each accessed via its unique address. @@ -15,7 +15,6 @@ in theory, a bus can support 128 devices, each accessed via its unique address. UAVCAN would normally be preferred where higher data rates are required, and on larger vehicles where sensors are mounted further from the flight controller. ::: - ## Wiring I2C uses a pair of wires: SDA (serial data) and SCL (serial clock). @@ -29,7 +28,6 @@ To ensure reliable communication and to reduce crosstalk it is advised to apply ![Cable twisting](../../assets/hardware/cables/i2c_jst-gh_cable.jpg) - ## Checking the Bus and Device Status A useful tool for bus analysis is [i2cdetect](../modules/modules_command.md#i2cdetect). @@ -41,8 +39,8 @@ The tool can be run in the PX4 terminal with the following command: ``` i2cdetect -b 1 ``` -where the bus number is specified after `-b` parameter +where the bus number is specified after `-b` parameter ## Common problems @@ -62,8 +60,9 @@ The bandwidth available for each device generally decreases as more devices are If too many devices are added, it can cause transmission errors and network unreliability. There are several ways to reduce the problem: -* Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port -* Increase bus speed limit (usually set to 100kHz for external I2C bus) + +- Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port +- Increase bus speed limit (usually set to 100kHz for external I2C bus) ### Excessive Wiring Capacitance @@ -71,9 +70,10 @@ The electrical capacity of bus wiring increases as more devices/wires are added. The problem can be analyzed using an oscilloscope, where we see that the edges of SDA/SCL signals are no longer sharp. There are several ways to reduce the problem: -* Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port -* Using the shorter and higher quality I2C cables, see the [cable wiring page](../assembly/cable_wiring.md#i2c-cables) for details -* Separating the devices with a weak open-drain driver to smaller buses with lower capacitance by using [I2C Bus Accelerators](#i2c-bus-accelerators) + +- Dividing the devices into groups, each with approximately the same number of devices, and connecting each group to one autopilot port +- Using the shorter and higher quality I2C cables, see the [cable wiring page](../assembly/cable_wiring.md#i2c-cables) for details +- Separating the devices with a weak open-drain driver to smaller buses with lower capacitance by using [I2C Bus Accelerators](#i2c-bus-accelerators) ## I2C Bus Accelerators @@ -81,6 +81,7 @@ I2C bus accelerators are separate circuits that can be used to support longer wi They work by physically dividing an I2C network into 2 parts and using their own transistors to amplify I2C signals. Available accelerators include: + - [Thunderfly TFI2CEXT01](https://docs.thunderfly.cz/avionics/TFI2CEXT01/): ![I2C bus extender](../../assets/peripherals/i2c_tfi2cext/tfi2cext01a_bottom.jpg) - This has Dronecode connectors and is hence very easy to add to a Pixhawk I2C setup. @@ -89,7 +90,7 @@ Available accelerators include: ### I2C Level Converter function Some I2C devices have 5V on the data lines, while the Pixhawk connector standard port expects these lines to be 3.3 V. -You can use the TFI2CEXT01 as a level converter to connect 5V devices to a Pixhawk I2C port. This feature is possible because the SCL and SDA lines of TFI2CEXT01 are 5V tolerant. +You can use the TFI2CEXT01 as a level converter to connect 5V devices to a Pixhawk I2C port. This feature is possible because the SCL and SDA lines of TFI2CEXT01 are 5V tolerant. ## I2C Address Translators @@ -112,6 +113,6 @@ Software development for I2C devices is described in [I2C Bus (Development Overv ## Further Information -* [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) -* [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) -* [Driver Framework](../middleware/drivers.md) +- [I2C](https://en.wikipedia.org/wiki/I%C2%B2C) (Wikipedia) +- [I2C Comparative Overview](https://learn.sparkfun.com/tutorials/i2c) (learn.sparkfun.com) +- [Driver Framework](../middleware/drivers.md) diff --git a/docs/en/sensor_bus/translator_tfi2cadt.md b/docs/en/sensor_bus/translator_tfi2cadt.md index 0f00b6a610b4..0c12106d787b 100644 --- a/docs/en/sensor_bus/translator_tfi2cadt.md +++ b/docs/en/sensor_bus/translator_tfi2cadt.md @@ -28,7 +28,7 @@ If you need your own value for address translation, changing the configuration r ## Example of Use The tachometer sensor [TFRPM01](../sensor/thunderfly_tachometer.md) can be set to two different addresses using a solder jumper. -If the autopilot has three buses, only 6 sensors can be connected and no bus remains free (2 available addresses * 3 I2C ports). +If the autopilot has three buses, only 6 sensors can be connected and no bus remains free (2 available addresses \* 3 I2C ports). In some multicopters or VTOL solutions, there is a need to measure the RPM of 8 or more elements. The [TFI2CADT01](https://www.tindie.com/products/26353/) is highly recommended in this case. @@ -39,7 +39,6 @@ By adding another TFI2CADT01, 4 more devices can be connected to the same bus. [![Connection of multiple sensors](https://mermaid.ink/img/pako:eNptkd9rwjAQx_-VcE8dtJB2ukEfBLEWfJCJy8CHvgRznQH7gzSBDfF_33VZB2oCyf3I576XcBc4dgohh08j-xMTRdUyWuX2I6LNErY7zJh0tuv1ubNP_7csSRZsudlHS22GHlGxAduhM3fEfrdNI1GS4emK8a85fwSyGyC9A0S5yVbrg_DZKfLtCxH9JsjhaU7VvI7pfK3_NCg_NXmO3pwl5uYt9D0yAXoWoFNP4yM9H-kspJ0FtF8CdObpURtiaNA0UisaymWsrsCesMEKcnIV1tKdbQVVeyXU9UpaXCttOwO5NQ5jGKf1_t0ep9gzhZY04sYnrz9BI4mU)](https://mermaid-js.github.io/mermaid-live-editor/edit#pako:eNptkd9rwjAQx_-VcE8dtJB2ukEfBLEWfJCJy8CHvgRznQH7gzSBDfF_33VZB2oCyf3I576XcBc4dgohh08j-xMTRdUyWuX2I6LNErY7zJh0tuv1ubNP_7csSRZsudlHS22GHlGxAduhM3fEfrdNI1GS4emK8a85fwSyGyC9A0S5yVbrg_DZKfLtCxH9JsjhaU7VvI7pfK3_NCg_NXmO3pwl5uYt9D0yAXoWoFNP4yM9H-kspJ0FtF8CdObpURtiaNA0UisaymWsrsCesMEKcnIV1tKdbQVVeyXU9UpaXCttOwO5NQ5jGKf1_t0ep9gzhZY04sYnrz9BI4mU) - - ::: info TFI2CADT01 does not contain any I2C buffer or accelerator. As it adds additional capacitance on the bus, we advise combining it with some bus booster, e.g. [TFI2CEXT01](https://docs.thunderfly.cz/avionics/TFI2CEXT01/). @@ -62,4 +60,4 @@ As it adds additional capacitance on the bus, we advise combining it with some b ### Other Resources -* Datasheet of [LTC4317](https://www.analog.com/media/en/technical-documentation/data-sheets/4317fa.pdf) +- Datasheet of [LTC4317](https://www.analog.com/media/en/technical-documentation/data-sheets/4317fa.pdf) diff --git a/docs/en/sim_gazebo_gz/index.md b/docs/en/sim_gazebo_gz/index.md index 6f5dead778e2..8f4ed2fee8a1 100644 --- a/docs/en/sim_gazebo_gz/index.md +++ b/docs/en/sim_gazebo_gz/index.md @@ -68,7 +68,6 @@ Note that all gazebo make targets have the prefix `gz_`. | [Ackermann Rover](../sim_gazebo_gz/vehicles.md#ackermann-rover) | `make px4_sitl gz_rover_ackermann` | 51000 | | [Mecanum Rover](../sim_gazebo_gz/vehicles.md#mecanum-rover) | `make px4_sitl gz_rover_mecanum` | 52000 | - All [vehicle models](../sim_gazebo_gz/vehicles.md) (and [worlds](#specify-world)) are included as a submodule from the [Gazebo Models Repository](../sim_gazebo_gz/gazebo_models.md) repository. The commands above launch a single vehicle with the full UI. @@ -136,6 +135,7 @@ HEADLESS=1 make px4_sitl gz_x500 ``` ### Set Custom Takeoff Location + The takeoff location in Gazebo Classic can be set using environment variables. The variables to set are: PX4_HOME_LAT, PX4_HOME_LON, and PX4_HOME_ALT. @@ -254,13 +254,11 @@ where `ARGS` is a list of environment variables including: - `PX4_GZ_MODEL_NAME`: Sets the name of an _existing_ model in the gazebo simulation. If provided, the startup script tries to bind a new PX4 instance to the Gazebo resource matching exactly that name. - - The setting is mutually exclusive with `PX4_SIM_MODEL`. - `PX4_SIM_MODEL`: Sets the name of a new Gazebo model to be spawned in the simulator. If provided, the startup script looks for a model in the Gazebo resource path that matches the given variable, spawns it and binds a new PX4 instance to it. - - The setting is mutually exclusive with `PX4_GZ_MODEL_NAME`. ::: info @@ -270,7 +268,6 @@ where `ARGS` is a list of environment variables including: - `PX4_GZ_MODEL_POSE`: Sets the spawning position and orientation of the model when `PX4_SIM_MODEL` is adopted. If provided, the startup script spawns the model at a pose following the syntax `"x,y,z,roll,pitch,yaw"`, where the positions are given in metres and the angles are in radians. - - If omitted, the zero pose `[0,0,0,0,0,0]` is used. - If less then 6 values are provided, the missing ones are fixed to zero. - This can only be used with `PX4_SIM_MODEL` (not `PX4_GZ_MODEL_NAME`). @@ -278,7 +275,6 @@ where `ARGS` is a list of environment variables including: - `PX4_GZ_WORLD`: Sets the Gazebo world file for a new simulation. If it is not given, then [default](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/default.sdf) is used. - - This variable is ignored if an existing simulation is already running. - This value should be [specified for the selected airframe](#adding-new-worlds-and-models) but may be overridden using this argument. - If the [moving platform world](../sim_gazebo_gz/worlds.md#moving-platform) is selected using `PX4_GZ_WORLD=moving_platform` (or any world using the moving platform plugin), the platform can be configured using environment variables: @@ -287,7 +283,6 @@ where `ARGS` is a list of environment variables including: - `PX4_SIMULATOR=GZ`: Sets the simulator, which for Gazebo must be `gz`. - - This value should be [set for the selected airframe](#adding-new-worlds-and-models), in which case it does not need to be set as an argument. - `PX4_GZ_STANDALONE`: @@ -375,7 +370,6 @@ To add a new model: ``` 1. Add CMake Target for the [airframe](https://github.com/PX4/PX4-Autopilot/blob/main/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt). - - If you plan to use "regular" mode, add your model SDF to `Tools/simulation/gz/models/`. - If you plan to use _standalone_ mode, add your model SDF to `~/.simulation-gazebo/models/` @@ -387,7 +381,6 @@ To add a new world: 1. Add your world to the list of worlds found in the [`CMakeLists.txt` here](https://github.com/PX4/PX4-Autopilot/blob/main/src/modules/simulation/gz_bridge/CMakeLists.txt). This is required in order to allow `CMake` to generate correct targets. - - If you plan to use "normal" mode, add your world sdf to `Tools/simulation/gz/worlds/`. - If you plan to use _standalone_ mode, add your world SDF to `~/.simulation-gazebo/worlds/` diff --git a/docs/en/sim_gazebo_gz/worlds.md b/docs/en/sim_gazebo_gz/worlds.md index 5f72e222b2d3..8d10d5075491 100644 --- a/docs/en/sim_gazebo_gz/worlds.md +++ b/docs/en/sim_gazebo_gz/worlds.md @@ -85,8 +85,8 @@ PX4_GZ_MODEL_POSE=0,0,2.2 PX4_GZ_WORLD=moving_platform make px4_sitl gz_standard The plugin can be configured with the following environment variables: - - `PX4_GZ_PLATFORM_VEL`: Platform speed (m/s). - - `PX4_GZ_PLATFORM_HEADING_DEG`: Platform heading and direction of velocity (degrees). 0 = east, positive direction is counterclockwise. +- `PX4_GZ_PLATFORM_VEL`: Platform speed (m/s). +- `PX4_GZ_PLATFORM_HEADING_DEG`: Platform heading and direction of velocity (degrees). 0 = east, positive direction is counterclockwise. [PX4-gazebo-models/main/worlds/moving_platform.sdf](https://github.com/PX4/PX4-gazebo-models/blob/main/worlds/moving_platform.sdf) diff --git a/docs/en/simulation/community_supported_simulators.md b/docs/en/simulation/community_supported_simulators.md index 6e201601c220..a7bbda97c09e 100644 --- a/docs/en/simulation/community_supported_simulators.md +++ b/docs/en/simulation/community_supported_simulators.md @@ -12,10 +12,10 @@ See [Toolchain Installation](../dev_setup/dev_env.md) for information about the The tools have variable levels of support from their communities (some are well supported and others are not). Questions about these tools should be raised on the [discussion forums](../contribute/support.md#forums-and-chat) -| Simulator | Description | -| --------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- | -| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL, Ackermann Rover

| -| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| -| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| -| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| -| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| +| Simulator | Description | +| --------------------------------------------------- | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ | +| [Simulation-In-Hardware](../sim_sih/index.md) (SIH) |

A simulator implemented in C++ as a PX4 module directly in the Firmware [code](https://github.com/PX4/PX4-Autopilot/tree/main/src/modules/simulation/simulator_sih). It can be ran in SITL directly on the computer or as an alternative to HITL offering a hard real-time simulation directly on the hardware autopilot.

Supported Vehicles: Quad, Hexa, Plane, Tailsitter, Standard VTOL, Ackermann Rover

| +| [FlightGear](../sim_flightgear/index.md) |

A simulator that provides physically and visually realistic simulations. In particular it can simulate many weather conditions, including thunderstorms, snow, rain and hail, and can also simulate thermals and different types of atmospheric flows. [Multi-vehicle simulation](../sim_flightgear/multi_vehicle.md) is also supported.

Supported Vehicles: Plane, Autogyro, Rover

| +| [JMAVSim](../sim_jmavsim/index.md) |

A simple multirotor/quad simulator. This was previously part of the PX4 development toolchain but was removed in favour of [Gazebo](../sim_gazebo_gz/index.md).

Supported Vehicles: Quad

| +| [JSBSim](../sim_jsbsim/index.md) |

A simulator that provides advanced flight dynamics models. This can be used to model realistic flight dynamics based on wind tunnel data.

Supported Vehicles: Plane, Quad, Hex

| +| [AirSim](../sim_airsim/index.md) |

A cross platform simulator that provides physically and visually realistic simulations. This simulator is resource intensive, and requires a significantly more powerful computer than the other simulators described here.

Supported Vehicles: Iris (MultiRotor model and a configuration for PX4 QuadRotor in the X configuration).

| diff --git a/docs/en/smart_batteries/index.md b/docs/en/smart_batteries/index.md index 6ddc0328427f..805ad60619b4 100644 --- a/docs/en/smart_batteries/index.md +++ b/docs/en/smart_batteries/index.md @@ -5,7 +5,8 @@ This allows for more more reliable flight planning notification of failure condi The information may include some of: remaining charge, time-to-empty (estimated), cell voltages (rated max/min, current voltage, etc.), temperature, currents, fault information, battery vendor, chemistry, etc. PX4 supports (at least) following smart batteries: -* [Rotoye Batmon](../smart_batteries/rotoye_batmon.md) + +- [Rotoye Batmon](../smart_batteries/rotoye_batmon.md) ### Further Information diff --git a/docs/en/smart_batteries/rotoye_batmon.md b/docs/en/smart_batteries/rotoye_batmon.md index 64120b5da859..a50eba58e28b 100644 --- a/docs/en/smart_batteries/rotoye_batmon.md +++ b/docs/en/smart_batteries/rotoye_batmon.md @@ -7,12 +7,10 @@ It can be purchased as a standalone unit or as part of a factory-assembled smart ![Pre-assembled Rotoye smart battery](../../assets/hardware/smart_batteries/rotoye_batmon/smart-battery-rotoye-pack.jpg) - ## Where to Buy [Rotoye Store](https://rotoye.com/batmon/): Batmon kits, custom smart-batteries, and accessories - ## Wiring/Connections The Rotoye Batmon system uses an XT-90 battery connector with I2C pins, and an opti-isolator board to transmit data. @@ -21,7 +19,6 @@ The Rotoye Batmon system uses an XT-90 battery connector with I2C pins, and an o More details can be found [here](https://github.com/rotoye/batmon_reader) - ## Software Setup ### Build PX4 Firmware @@ -31,7 +28,7 @@ More details can be found [here](https://github.com/rotoye/batmon_reader) git clone https://github.com/rotoye/PX4-Autopilot.git cd PX4-Autopilot ``` -1. Checkout the *batmon_4.03* branch +1. Checkout the _batmon_4.03_ branch ```sh git fetch origin batmon_4.03 git checkout batmon_4.03 @@ -40,16 +37,17 @@ More details can be found [here](https://github.com/rotoye/batmon_reader) ### Configure Parameters -In *QGroundControl*: +In _QGroundControl_: + 1. Set the following [parameters](../advanced_config/parameters.md): - `BATx_SOURCE` to `External`, - - `SENS_EN_BAT` to `true`, + - `SENS_EN_BAT` to `true`, - `BAT_SMBUS_MODEL` to `3:Rotoye` 1. Open the [MAVLink Console](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/analyze_view/mavlink_console.html) 1. Start the [batt_smbus driver](../modules/modules_driver.md) in the console. For example, to run two BatMons on the same bus: - ```sh - batt_smbus start -X -b 1 -a 11 # External bus 1, address 0x0b + ```sh + batt_smbus start -X -b 1 -a 11 # External bus 1, address 0x0b batt_smbus start -X -b 1 -a 12 # External bus 1, address 0x0c ``` diff --git a/docs/en/test_and_ci/index.md b/docs/en/test_and_ci/index.md index a906ed8f465b..dbb1aa7c11f3 100644 --- a/docs/en/test_and_ci/index.md +++ b/docs/en/test_and_ci/index.md @@ -9,8 +9,8 @@ Test topics include: - [Unit Tests](../test_and_ci/unit_tests.md) - [Continuous Integration (CI)](../test_and_ci/continous_integration.md) - [Integration Testing](../test_and_ci/integration_testing.md) - - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) - - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) - - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) + - [MAVSDK Integration Testing](../test_and_ci/integration_testing_mavsdk.md) + - [PX4 ROS2 Interface Library Integration Testing](../test_and_ci/integration_testing_px4_ros2_interface.md) + - [ROS 1 Integration Testing](../test_and_ci/integration_testing_ros1_mavros.md) (Deprecated) - [Docker](../test_and_ci/docker.md) - [Maintenance](../test_and_ci/maintenance.md) diff --git a/docs/en/test_cards/mc_04_failsafe_testing.md b/docs/en/test_cards/mc_04_failsafe_testing.md index 4042e094d22b..3947be6b2ef1 100644 --- a/docs/en/test_cards/mc_04_failsafe_testing.md +++ b/docs/en/test_cards/mc_04_failsafe_testing.md @@ -9,10 +9,10 @@ Test RC loss, data link loss, and low battery failsafes. - Verify RC Loss action is Return to Land - Verify Data Link Loss action is Return to Land and the timeout is 10 seconds - Verify Battery failsafe - - Action is Return to Land - - Battery Warn Level is 25% - - Battery Failsafe Level is 20% - - Battery Emergency Level is 15% + - Action is Return to Land + - Battery Warn Level is 25% + - Battery Failsafe Level is 20% + - Battery Emergency Level is 15% ## Flight Tests @@ -28,7 +28,6 @@ Test RC loss, data link loss, and low battery failsafes.     ❏ Disconnect telemetry, vehicle should return to home position after 10 seconds, wait for the descent and reconnect the telemetry radio - ❏ Battery Failsafe     ❏ Confirm the warning message is received in QGC diff --git a/docs/en/uart/user_configurable_serial_driver.md b/docs/en/uart/user_configurable_serial_driver.md index 9fbe168a6666..3809ad25a6e7 100644 --- a/docs/en/uart/user_configurable_serial_driver.md +++ b/docs/en/uart/user_configurable_serial_driver.md @@ -24,7 +24,6 @@ where, To make driver configurable: 1. Create a YAML module configuration file: - - Add a new file in the driver's source directory named **module.yaml** - Insert the following text and adjust as needed: diff --git a/docs/package-lock.json b/docs/package-lock.json deleted file mode 100644 index 2a87516fb02e..000000000000 --- a/docs/package-lock.json +++ /dev/null @@ -1,3297 +0,0 @@ -{ - "name": "px4_user_guide", - "version": "1.0.1", - "lockfileVersion": 3, - "requires": true, - "packages": { - "": { - "name": "px4_user_guide", - "version": "1.0.1", - "license": "CC-BY-4.0", - "dependencies": { - "@red-asuka/vitepress-plugin-tabs": "0.0.4", - "lite-youtube-embed": "^0.3.3", - "markdown-it-mathjax3": "^4.3.2", - "medium-zoom": "^1.1.0", - "open-editor": "^5.0.0", - "vitepress": "^1.6.3", - "vue3-tabs-component": "^1.3.7" - } - }, - "node_modules/@algolia/autocomplete-core": { - "version": "1.17.7", - "resolved": "https://registry.npmjs.org/@algolia/autocomplete-core/-/autocomplete-core-1.17.7.tgz", - "integrity": "sha512-BjiPOW6ks90UKl7TwMv7oNQMnzU+t/wk9mgIDi6b1tXpUek7MW0lbNOUHpvam9pe3lVCf4xPFT+lK7s+e+fs7Q==", - "license": "MIT", - "dependencies": { - "@algolia/autocomplete-plugin-algolia-insights": "1.17.7", - "@algolia/autocomplete-shared": "1.17.7" - } - }, - "node_modules/@algolia/autocomplete-plugin-algolia-insights": { - "version": "1.17.7", - "resolved": "https://registry.npmjs.org/@algolia/autocomplete-plugin-algolia-insights/-/autocomplete-plugin-algolia-insights-1.17.7.tgz", - "integrity": "sha512-Jca5Ude6yUOuyzjnz57og7Et3aXjbwCSDf/8onLHSQgw1qW3ALl9mrMWaXb5FmPVkV3EtkD2F/+NkT6VHyPu9A==", - "license": "MIT", - "dependencies": { - "@algolia/autocomplete-shared": "1.17.7" - }, - "peerDependencies": { - "search-insights": ">= 1 < 3" - } - }, - "node_modules/@algolia/autocomplete-preset-algolia": { - "version": "1.17.7", - "resolved": "https://registry.npmjs.org/@algolia/autocomplete-preset-algolia/-/autocomplete-preset-algolia-1.17.7.tgz", - "integrity": "sha512-ggOQ950+nwbWROq2MOCIL71RE0DdQZsceqrg32UqnhDz8FlO9rL8ONHNsI2R1MH0tkgVIDKI/D0sMiUchsFdWA==", - "license": "MIT", - "dependencies": { - "@algolia/autocomplete-shared": "1.17.7" - }, - "peerDependencies": { - "@algolia/client-search": ">= 4.9.1 < 6", - "algoliasearch": ">= 4.9.1 < 6" - } - }, - "node_modules/@algolia/autocomplete-shared": { - "version": "1.17.7", - "resolved": "https://registry.npmjs.org/@algolia/autocomplete-shared/-/autocomplete-shared-1.17.7.tgz", - "integrity": "sha512-o/1Vurr42U/qskRSuhBH+VKxMvkkUVTLU6WZQr+L5lGZZLYWyhdzWjW0iGXY7EkwRTjBqvN2EsR81yCTGV/kmg==", - "license": "MIT", - "peerDependencies": { - "@algolia/client-search": ">= 4.9.1 < 6", - "algoliasearch": ">= 4.9.1 < 6" - } - }, - "node_modules/@algolia/client-abtesting": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-abtesting/-/client-abtesting-5.32.0.tgz", - "integrity": "sha512-HG/6Eib6DnJYm/B2ijWFXr4txca/YOuA4K7AsEU0JBrOZSB+RU7oeDyNBPi3c0v0UDDqlkBqM3vBU/auwZlglA==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/client-analytics": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-analytics/-/client-analytics-5.32.0.tgz", - "integrity": "sha512-8Y9MLU72WFQOW3HArYv16+Wvm6eGmsqbxxM1qxtm0hvSASJbxCm+zQAZe5stqysTlcWo4BJ82KEH1PfgHbJAmQ==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/client-common": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-common/-/client-common-5.32.0.tgz", - "integrity": "sha512-w8L+rgyXMCPBKmEdOT+RfgMrF0mT6HK60vPYWLz8DBs/P7yFdGo7urn99XCJvVLMSKXrIbZ2FMZ/i50nZTXnuQ==", - "license": "MIT", - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/client-insights": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-insights/-/client-insights-5.32.0.tgz", - "integrity": "sha512-AdWfynhUeX7jz/LTiFU3wwzJembTbdLkQIOLs4n7PyBuxZ3jz4azV1CWbIP8AjUOFmul6uXbmYza+KqyS5CzOA==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/client-personalization": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-personalization/-/client-personalization-5.32.0.tgz", - "integrity": "sha512-bTupJY4xzGZYI4cEQcPlSjjIEzMvv80h7zXGrXY1Y0KC/n/SLiMv84v7Uy+B6AG1Kiy9FQm2ADChBLo1uEhGtQ==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/client-query-suggestions": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-query-suggestions/-/client-query-suggestions-5.32.0.tgz", - "integrity": "sha512-if+YTJw1G3nDKL2omSBjQltCHUQzbaHADkcPQrGFnIGhVyHU3Dzq4g46uEv8mrL5sxL8FjiS9LvekeUlL2NRqw==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/client-search": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/client-search/-/client-search-5.32.0.tgz", - "integrity": "sha512-kmK5nVkKb4DSUgwbveMKe4X3xHdMsPsOVJeEzBvFJ+oS7CkBPmpfHAEq+CcmiPJs20YMv6yVtUT9yPWL5WgAhg==", - "license": "MIT", - "peer": true, - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/ingestion": { - "version": "1.32.0", - "resolved": "https://registry.npmjs.org/@algolia/ingestion/-/ingestion-1.32.0.tgz", - "integrity": "sha512-PZTqjJbx+fmPuT2ud1n4vYDSF1yrT//vOGI9HNYKNA0PM0xGUBWigf5gRivHsXa3oBnUlTyHV9j7Kqx5BHbVHQ==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/monitoring": { - "version": "1.32.0", - "resolved": "https://registry.npmjs.org/@algolia/monitoring/-/monitoring-1.32.0.tgz", - "integrity": "sha512-kYYoOGjvNQAmHDS1v5sBj+0uEL9RzYqH/TAdq8wmcV+/22weKt/fjh+6LfiqkS1SCZFYYrwGnirrUhUM36lBIQ==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/recommend": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/recommend/-/recommend-5.32.0.tgz", - "integrity": "sha512-jyIBLdskjPAL7T1g57UMfUNx+PzvYbxKslwRUKBrBA6sNEsYCFdxJAtZSLUMmw6MC98RDt4ksmEl5zVMT5bsuw==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/requester-browser-xhr": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/requester-browser-xhr/-/requester-browser-xhr-5.32.0.tgz", - "integrity": "sha512-eDp14z92Gt6JlFgiexImcWWH+Lk07s/FtxcoDaGrE4UVBgpwqOO6AfQM6dXh1pvHxlDFbMJihHc/vj3gBhPjqQ==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/requester-fetch": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/requester-fetch/-/requester-fetch-5.32.0.tgz", - "integrity": "sha512-rnWVglh/K75hnaLbwSc2t7gCkbq1ldbPgeIKDUiEJxZ4mlguFgcltWjzpDQ/t1LQgxk9HdIFcQfM17Hid3aQ6Q==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@algolia/requester-node-http": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/@algolia/requester-node-http/-/requester-node-http-5.32.0.tgz", - "integrity": "sha512-LbzQ04+VLkzXY4LuOzgyjqEv/46Gwrk55PldaglMJ4i4eDXSRXGKkwJpXFwsoU+c1HMQlHIyjJBhrfsfdyRmyQ==", - "license": "MIT", - "dependencies": { - "@algolia/client-common": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/@babel/helper-string-parser": { - "version": "7.27.1", - "resolved": "https://registry.npmjs.org/@babel/helper-string-parser/-/helper-string-parser-7.27.1.tgz", - "integrity": "sha512-qMlSxKbpRlAridDExk92nSobyDdpPijUq2DW6oDnUqd0iOGxmQjyqhMIihI9+zv4LPyZdRje2cavWPbCbWm3eA==", - "license": "MIT", - "engines": { - "node": ">=6.9.0" - } - }, - "node_modules/@babel/helper-validator-identifier": { - "version": "7.27.1", - "resolved": "https://registry.npmjs.org/@babel/helper-validator-identifier/-/helper-validator-identifier-7.27.1.tgz", - "integrity": "sha512-D2hP9eA+Sqx1kBZgzxZh0y1trbuU+JoDkiEwqhQ36nodYqJwyEIhPSdMNd7lOm/4io72luTPWH20Yda0xOuUow==", - "license": "MIT", - "engines": { - "node": ">=6.9.0" - } - }, - "node_modules/@babel/parser": { - "version": "7.28.0", - "resolved": "https://registry.npmjs.org/@babel/parser/-/parser-7.28.0.tgz", - "integrity": "sha512-jVZGvOxOuNSsuQuLRTh13nU0AogFlw32w/MT+LV6D3sP5WdbW61E77RnkbaO2dUvmPAYrBDJXGn5gGS6tH4j8g==", - "license": "MIT", - "dependencies": { - "@babel/types": "^7.28.0" - }, - "bin": { - "parser": "bin/babel-parser.js" - }, - "engines": { - "node": ">=6.0.0" - } - }, - "node_modules/@babel/types": { - "version": "7.28.0", - "resolved": "https://registry.npmjs.org/@babel/types/-/types-7.28.0.tgz", - "integrity": "sha512-jYnje+JyZG5YThjHiF28oT4SIZLnYOcSBb6+SDaFIyzDVSkXQmQQYclJ2R+YxcdmK0AX6x1E5OQNtuh3jHDrUg==", - "license": "MIT", - "dependencies": { - "@babel/helper-string-parser": "^7.27.1", - "@babel/helper-validator-identifier": "^7.27.1" - }, - "engines": { - "node": ">=6.9.0" - } - }, - "node_modules/@docsearch/css": { - "version": "3.8.2", - "resolved": "https://registry.npmjs.org/@docsearch/css/-/css-3.8.2.tgz", - "integrity": "sha512-y05ayQFyUmCXze79+56v/4HpycYF3uFqB78pLPrSV5ZKAlDuIAAJNhaRi8tTdRNXh05yxX/TyNnzD6LwSM89vQ==", - "license": "MIT" - }, - "node_modules/@docsearch/js": { - "version": "3.8.2", - "resolved": "https://registry.npmjs.org/@docsearch/js/-/js-3.8.2.tgz", - "integrity": "sha512-Q5wY66qHn0SwA7Taa0aDbHiJvaFJLOJyHmooQ7y8hlwwQLQ/5WwCcoX0g7ii04Qi2DJlHsd0XXzJ8Ypw9+9YmQ==", - "license": "MIT", - "dependencies": { - "@docsearch/react": "3.8.2", - "preact": "^10.0.0" - } - }, - "node_modules/@docsearch/react": { - "version": "3.8.2", - "resolved": "https://registry.npmjs.org/@docsearch/react/-/react-3.8.2.tgz", - "integrity": "sha512-xCRrJQlTt8N9GU0DG4ptwHRkfnSnD/YpdeaXe02iKfqs97TkZJv60yE+1eq/tjPcVnTW8dP5qLP7itifFVV5eg==", - "license": "MIT", - "dependencies": { - "@algolia/autocomplete-core": "1.17.7", - "@algolia/autocomplete-preset-algolia": "1.17.7", - "@docsearch/css": "3.8.2", - "algoliasearch": "^5.14.2" - }, - "peerDependencies": { - "@types/react": ">= 16.8.0 < 19.0.0", - "react": ">= 16.8.0 < 19.0.0", - "react-dom": ">= 16.8.0 < 19.0.0", - "search-insights": ">= 1 < 3" - }, - "peerDependenciesMeta": { - "@types/react": { - "optional": true - }, - "react": { - "optional": true - }, - "react-dom": { - "optional": true - }, - "search-insights": { - "optional": true - } - } - }, - "node_modules/@esbuild/aix-ppc64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/aix-ppc64/-/aix-ppc64-0.21.5.tgz", - "integrity": "sha512-1SDgH6ZSPTlggy1yI6+Dbkiz8xzpHJEVAlF/AM1tHPLsf5STom9rwtjE4hKAF20FfXXNTFqEYXyJNWh1GiZedQ==", - "cpu": [ - "ppc64" - ], - "license": "MIT", - "optional": true, - "os": [ - "aix" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/android-arm": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/android-arm/-/android-arm-0.21.5.tgz", - "integrity": "sha512-vCPvzSjpPHEi1siZdlvAlsPxXl7WbOVUBBAowWug4rJHb68Ox8KualB+1ocNvT5fjv6wpkX6o/iEpbDrf68zcg==", - "cpu": [ - "arm" - ], - "license": "MIT", - "optional": true, - "os": [ - "android" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/android-arm64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/android-arm64/-/android-arm64-0.21.5.tgz", - "integrity": "sha512-c0uX9VAUBQ7dTDCjq+wdyGLowMdtR/GoC2U5IYk/7D1H1JYC0qseD7+11iMP2mRLN9RcCMRcjC4YMclCzGwS/A==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "android" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/android-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/android-x64/-/android-x64-0.21.5.tgz", - "integrity": "sha512-D7aPRUUNHRBwHxzxRvp856rjUHRFW1SdQATKXH2hqA0kAZb1hKmi02OpYRacl0TxIGz/ZmXWlbZgjwWYaCakTA==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "android" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/darwin-arm64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/darwin-arm64/-/darwin-arm64-0.21.5.tgz", - "integrity": "sha512-DwqXqZyuk5AiWWf3UfLiRDJ5EDd49zg6O9wclZ7kUMv2WRFr4HKjXp/5t8JZ11QbQfUS6/cRCKGwYhtNAY88kQ==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "darwin" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/darwin-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/darwin-x64/-/darwin-x64-0.21.5.tgz", - "integrity": "sha512-se/JjF8NlmKVG4kNIuyWMV/22ZaerB+qaSi5MdrXtd6R08kvs2qCN4C09miupktDitvh8jRFflwGFBQcxZRjbw==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "darwin" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/freebsd-arm64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/freebsd-arm64/-/freebsd-arm64-0.21.5.tgz", - "integrity": "sha512-5JcRxxRDUJLX8JXp/wcBCy3pENnCgBR9bN6JsY4OmhfUtIHe3ZW0mawA7+RDAcMLrMIZaf03NlQiX9DGyB8h4g==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "freebsd" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/freebsd-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/freebsd-x64/-/freebsd-x64-0.21.5.tgz", - "integrity": "sha512-J95kNBj1zkbMXtHVH29bBriQygMXqoVQOQYA+ISs0/2l3T9/kj42ow2mpqerRBxDJnmkUDCaQT/dfNXWX/ZZCQ==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "freebsd" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-arm": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-arm/-/linux-arm-0.21.5.tgz", - "integrity": "sha512-bPb5AHZtbeNGjCKVZ9UGqGwo8EUu4cLq68E95A53KlxAPRmUyYv2D6F0uUI65XisGOL1hBP5mTronbgo+0bFcA==", - "cpu": [ - "arm" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-arm64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-arm64/-/linux-arm64-0.21.5.tgz", - "integrity": "sha512-ibKvmyYzKsBeX8d8I7MH/TMfWDXBF3db4qM6sy+7re0YXya+K1cem3on9XgdT2EQGMu4hQyZhan7TeQ8XkGp4Q==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-ia32": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-ia32/-/linux-ia32-0.21.5.tgz", - "integrity": "sha512-YvjXDqLRqPDl2dvRODYmmhz4rPeVKYvppfGYKSNGdyZkA01046pLWyRKKI3ax8fbJoK5QbxblURkwK/MWY18Tg==", - "cpu": [ - "ia32" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-loong64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-loong64/-/linux-loong64-0.21.5.tgz", - "integrity": "sha512-uHf1BmMG8qEvzdrzAqg2SIG/02+4/DHB6a9Kbya0XDvwDEKCoC8ZRWI5JJvNdUjtciBGFQ5PuBlpEOXQj+JQSg==", - "cpu": [ - "loong64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-mips64el": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-mips64el/-/linux-mips64el-0.21.5.tgz", - "integrity": "sha512-IajOmO+KJK23bj52dFSNCMsz1QP1DqM6cwLUv3W1QwyxkyIWecfafnI555fvSGqEKwjMXVLokcV5ygHW5b3Jbg==", - "cpu": [ - "mips64el" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-ppc64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-ppc64/-/linux-ppc64-0.21.5.tgz", - "integrity": "sha512-1hHV/Z4OEfMwpLO8rp7CvlhBDnjsC3CttJXIhBi+5Aj5r+MBvy4egg7wCbe//hSsT+RvDAG7s81tAvpL2XAE4w==", - "cpu": [ - "ppc64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-riscv64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-riscv64/-/linux-riscv64-0.21.5.tgz", - "integrity": "sha512-2HdXDMd9GMgTGrPWnJzP2ALSokE/0O5HhTUvWIbD3YdjME8JwvSCnNGBnTThKGEB91OZhzrJ4qIIxk/SBmyDDA==", - "cpu": [ - "riscv64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-s390x": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-s390x/-/linux-s390x-0.21.5.tgz", - "integrity": "sha512-zus5sxzqBJD3eXxwvjN1yQkRepANgxE9lgOW2qLnmr8ikMTphkjgXu1HR01K4FJg8h1kEEDAqDcZQtbrRnB41A==", - "cpu": [ - "s390x" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/linux-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/linux-x64/-/linux-x64-0.21.5.tgz", - "integrity": "sha512-1rYdTpyv03iycF1+BhzrzQJCdOuAOtaqHTWJZCWvijKD2N5Xu0TtVC8/+1faWqcP9iBCWOmjmhoH94dH82BxPQ==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/netbsd-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/netbsd-x64/-/netbsd-x64-0.21.5.tgz", - "integrity": "sha512-Woi2MXzXjMULccIwMnLciyZH4nCIMpWQAs049KEeMvOcNADVxo0UBIQPfSmxB3CWKedngg7sWZdLvLczpe0tLg==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "netbsd" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/openbsd-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/openbsd-x64/-/openbsd-x64-0.21.5.tgz", - "integrity": "sha512-HLNNw99xsvx12lFBUwoT8EVCsSvRNDVxNpjZ7bPn947b8gJPzeHWyNVhFsaerc0n3TsbOINvRP2byTZ5LKezow==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "openbsd" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/sunos-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/sunos-x64/-/sunos-x64-0.21.5.tgz", - "integrity": "sha512-6+gjmFpfy0BHU5Tpptkuh8+uw3mnrvgs+dSPQXQOv3ekbordwnzTVEb4qnIvQcYXq6gzkyTnoZ9dZG+D4garKg==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "sunos" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/win32-arm64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/win32-arm64/-/win32-arm64-0.21.5.tgz", - "integrity": "sha512-Z0gOTd75VvXqyq7nsl93zwahcTROgqvuAcYDUr+vOv8uHhNSKROyU961kgtCD1e95IqPKSQKH7tBTslnS3tA8A==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "win32" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/win32-ia32": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/win32-ia32/-/win32-ia32-0.21.5.tgz", - "integrity": "sha512-SWXFF1CL2RVNMaVs+BBClwtfZSvDgtL//G/smwAc5oVK/UPu2Gu9tIaRgFmYFFKrmg3SyAjSrElf0TiJ1v8fYA==", - "cpu": [ - "ia32" - ], - "license": "MIT", - "optional": true, - "os": [ - "win32" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@esbuild/win32-x64": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/@esbuild/win32-x64/-/win32-x64-0.21.5.tgz", - "integrity": "sha512-tQd/1efJuzPC6rCFwEvLtci/xNFcTZknmXs98FYDfGE4wP9ClFV98nyKrzJKVPMhdDnjzLhdUyMX4PsQAPjwIw==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "win32" - ], - "engines": { - "node": ">=12" - } - }, - "node_modules/@iconify-json/simple-icons": { - "version": "1.2.42", - "resolved": "https://registry.npmjs.org/@iconify-json/simple-icons/-/simple-icons-1.2.42.tgz", - "integrity": "sha512-G/EED0hUV1wMNUsWaFdQYLibm6SO7rP2GZP1+CvhszB5WAFYYibD3zoWp3X96xSIWpYQFvccvE17ewpd0Q1hWQ==", - "license": "CC0-1.0", - "dependencies": { - "@iconify/types": "*" - } - }, - "node_modules/@iconify/types": { - "version": "2.0.0", - "resolved": "https://registry.npmjs.org/@iconify/types/-/types-2.0.0.tgz", - "integrity": "sha512-+wluvCrRhXrhyOmRDJ3q8mux9JkKy5SJ/v8ol2tu4FVjyYvtEzkc/3pK15ET6RKg4b4w4BmTk1+gsCUhf21Ykg==", - "license": "MIT" - }, - "node_modules/@jridgewell/sourcemap-codec": { - "version": "1.5.4", - "resolved": "https://registry.npmjs.org/@jridgewell/sourcemap-codec/-/sourcemap-codec-1.5.4.tgz", - "integrity": "sha512-VT2+G1VQs/9oz078bLrYbecdZKs912zQlkelYpuf+SXF+QvZDYJlbx/LSx+meSAwdDFnF8FVXW92AVjjkVmgFw==", - "license": "MIT" - }, - "node_modules/@red-asuka/vitepress-plugin-tabs": { - "version": "0.0.4", - "resolved": "https://registry.npmjs.org/@red-asuka/vitepress-plugin-tabs/-/vitepress-plugin-tabs-0.0.4.tgz", - "integrity": "sha512-fcZAR281xnPiTm2ha8Wogg3PyFG5ZdJoeCGFeg7lOif53wXxo1obJQS98A8n/ujL//fFok/sDr1659Hbx6MD0Q==", - "license": "MIT", - "dependencies": { - "markdown-it": "^13.0.1", - "markdown-it-container": "^3.0.0" - } - }, - "node_modules/@rollup/rollup-android-arm-eabi": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm-eabi/-/rollup-android-arm-eabi-4.44.2.tgz", - "integrity": "sha512-g0dF8P1e2QYPOj1gu7s/3LVP6kze9A7m6x0BZ9iTdXK8N5c2V7cpBKHV3/9A4Zd8xxavdhK0t4PnqjkqVmUc9Q==", - "cpu": [ - "arm" - ], - "license": "MIT", - "optional": true, - "os": [ - "android" - ] - }, - "node_modules/@rollup/rollup-android-arm64": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm64/-/rollup-android-arm64-4.44.2.tgz", - "integrity": "sha512-Yt5MKrOosSbSaAK5Y4J+vSiID57sOvpBNBR6K7xAaQvk3MkcNVV0f9fE20T+41WYN8hDn6SGFlFrKudtx4EoxA==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "android" - ] - }, - "node_modules/@rollup/rollup-darwin-arm64": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-arm64/-/rollup-darwin-arm64-4.44.2.tgz", - "integrity": "sha512-EsnFot9ZieM35YNA26nhbLTJBHD0jTwWpPwmRVDzjylQT6gkar+zenfb8mHxWpRrbn+WytRRjE0WKsfaxBkVUA==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "darwin" - ] - }, - "node_modules/@rollup/rollup-darwin-x64": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-x64/-/rollup-darwin-x64-4.44.2.tgz", - "integrity": "sha512-dv/t1t1RkCvJdWWxQ2lWOO+b7cMsVw5YFaS04oHpZRWehI1h0fV1gF4wgGCTyQHHjJDfbNpwOi6PXEafRBBezw==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "darwin" - ] - }, - "node_modules/@rollup/rollup-freebsd-arm64": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-arm64/-/rollup-freebsd-arm64-4.44.2.tgz", - "integrity": "sha512-W4tt4BLorKND4qeHElxDoim0+BsprFTwb+vriVQnFFtT/P6v/xO5I99xvYnVzKWrK6j7Hb0yp3x7V5LUbaeOMg==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "freebsd" - ] - }, - "node_modules/@rollup/rollup-freebsd-x64": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-x64/-/rollup-freebsd-x64-4.44.2.tgz", - "integrity": "sha512-tdT1PHopokkuBVyHjvYehnIe20fxibxFCEhQP/96MDSOcyjM/shlTkZZLOufV3qO6/FQOSiJTBebhVc12JyPTA==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "freebsd" - ] - }, - "node_modules/@rollup/rollup-linux-arm-gnueabihf": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-gnueabihf/-/rollup-linux-arm-gnueabihf-4.44.2.tgz", - "integrity": "sha512-+xmiDGGaSfIIOXMzkhJ++Oa0Gwvl9oXUeIiwarsdRXSe27HUIvjbSIpPxvnNsRebsNdUo7uAiQVgBD1hVriwSQ==", - "cpu": [ - "arm" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-arm-musleabihf": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-musleabihf/-/rollup-linux-arm-musleabihf-4.44.2.tgz", - "integrity": "sha512-bDHvhzOfORk3wt8yxIra8N4k/N0MnKInCW5OGZaeDYa/hMrdPaJzo7CSkjKZqX4JFUWjUGm88lI6QJLCM7lDrA==", - "cpu": [ - "arm" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-arm64-gnu": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-gnu/-/rollup-linux-arm64-gnu-4.44.2.tgz", - "integrity": "sha512-NMsDEsDiYghTbeZWEGnNi4F0hSbGnsuOG+VnNvxkKg0IGDvFh7UVpM/14mnMwxRxUf9AdAVJgHPvKXf6FpMB7A==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-arm64-musl": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-musl/-/rollup-linux-arm64-musl-4.44.2.tgz", - "integrity": "sha512-lb5bxXnxXglVq+7imxykIp5xMq+idehfl+wOgiiix0191av84OqbjUED+PRC5OA8eFJYj5xAGcpAZ0pF2MnW+A==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-loongarch64-gnu": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-loongarch64-gnu/-/rollup-linux-loongarch64-gnu-4.44.2.tgz", - "integrity": "sha512-Yl5Rdpf9pIc4GW1PmkUGHdMtbx0fBLE1//SxDmuf3X0dUC57+zMepow2LK0V21661cjXdTn8hO2tXDdAWAqE5g==", - "cpu": [ - "loong64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-powerpc64le-gnu": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-powerpc64le-gnu/-/rollup-linux-powerpc64le-gnu-4.44.2.tgz", - "integrity": "sha512-03vUDH+w55s680YYryyr78jsO1RWU9ocRMaeV2vMniJJW/6HhoTBwyyiiTPVHNWLnhsnwcQ0oH3S9JSBEKuyqw==", - "cpu": [ - "ppc64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-riscv64-gnu": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-gnu/-/rollup-linux-riscv64-gnu-4.44.2.tgz", - "integrity": "sha512-iYtAqBg5eEMG4dEfVlkqo05xMOk6y/JXIToRca2bAWuqjrJYJlx/I7+Z+4hSrsWU8GdJDFPL4ktV3dy4yBSrzg==", - "cpu": [ - "riscv64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-riscv64-musl": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-musl/-/rollup-linux-riscv64-musl-4.44.2.tgz", - "integrity": "sha512-e6vEbgaaqz2yEHqtkPXa28fFuBGmUJ0N2dOJK8YUfijejInt9gfCSA7YDdJ4nYlv67JfP3+PSWFX4IVw/xRIPg==", - "cpu": [ - "riscv64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-s390x-gnu": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-s390x-gnu/-/rollup-linux-s390x-gnu-4.44.2.tgz", - "integrity": "sha512-evFOtkmVdY3udE+0QKrV5wBx7bKI0iHz5yEVx5WqDJkxp9YQefy4Mpx3RajIVcM6o7jxTvVd/qpC1IXUhGc1Mw==", - "cpu": [ - "s390x" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-x64-gnu": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-gnu/-/rollup-linux-x64-gnu-4.44.2.tgz", - "integrity": "sha512-/bXb0bEsWMyEkIsUL2Yt5nFB5naLAwyOWMEviQfQY1x3l5WsLKgvZf66TM7UTfED6erckUVUJQ/jJ1FSpm3pRQ==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-linux-x64-musl": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-musl/-/rollup-linux-x64-musl-4.44.2.tgz", - "integrity": "sha512-3D3OB1vSSBXmkGEZR27uiMRNiwN08/RVAcBKwhUYPaiZ8bcvdeEwWPvbnXvvXHY+A/7xluzcN+kaiOFNiOZwWg==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "linux" - ] - }, - "node_modules/@rollup/rollup-win32-arm64-msvc": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-arm64-msvc/-/rollup-win32-arm64-msvc-4.44.2.tgz", - "integrity": "sha512-VfU0fsMK+rwdK8mwODqYeM2hDrF2WiHaSmCBrS7gColkQft95/8tphyzv2EupVxn3iE0FI78wzffoULH1G+dkw==", - "cpu": [ - "arm64" - ], - "license": "MIT", - "optional": true, - "os": [ - "win32" - ] - }, - "node_modules/@rollup/rollup-win32-ia32-msvc": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-ia32-msvc/-/rollup-win32-ia32-msvc-4.44.2.tgz", - "integrity": "sha512-+qMUrkbUurpE6DVRjiJCNGZBGo9xM4Y0FXU5cjgudWqIBWbcLkjE3XprJUsOFgC6xjBClwVa9k6O3A7K3vxb5Q==", - "cpu": [ - "ia32" - ], - "license": "MIT", - "optional": true, - "os": [ - "win32" - ] - }, - "node_modules/@rollup/rollup-win32-x64-msvc": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-msvc/-/rollup-win32-x64-msvc-4.44.2.tgz", - "integrity": "sha512-3+QZROYfJ25PDcxFF66UEk8jGWigHJeecZILvkPkyQN7oc5BvFo4YEXFkOs154j3FTMp9mn9Ky8RCOwastduEA==", - "cpu": [ - "x64" - ], - "license": "MIT", - "optional": true, - "os": [ - "win32" - ] - }, - "node_modules/@sec-ant/readable-stream": { - "version": "0.4.1", - "resolved": "https://registry.npmjs.org/@sec-ant/readable-stream/-/readable-stream-0.4.1.tgz", - "integrity": "sha512-831qok9r2t8AlxLko40y2ebgSDhenenCatLVeW/uBtnHPyhHOvG0C7TvfgecV+wHzIm5KUICgzmVpWS+IMEAeg==", - "license": "MIT" - }, - "node_modules/@shikijs/core": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/core/-/core-2.5.0.tgz", - "integrity": "sha512-uu/8RExTKtavlpH7XqnVYBrfBkUc20ngXiX9NSrBhOVZYv/7XQRKUyhtkeflY5QsxC0GbJThCerruZfsUaSldg==", - "license": "MIT", - "dependencies": { - "@shikijs/engine-javascript": "2.5.0", - "@shikijs/engine-oniguruma": "2.5.0", - "@shikijs/types": "2.5.0", - "@shikijs/vscode-textmate": "^10.0.2", - "@types/hast": "^3.0.4", - "hast-util-to-html": "^9.0.4" - } - }, - "node_modules/@shikijs/engine-javascript": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/engine-javascript/-/engine-javascript-2.5.0.tgz", - "integrity": "sha512-VjnOpnQf8WuCEZtNUdjjwGUbtAVKuZkVQ/5cHy/tojVVRIRtlWMYVjyWhxOmIq05AlSOv72z7hRNRGVBgQOl0w==", - "license": "MIT", - "dependencies": { - "@shikijs/types": "2.5.0", - "@shikijs/vscode-textmate": "^10.0.2", - "oniguruma-to-es": "^3.1.0" - } - }, - "node_modules/@shikijs/engine-oniguruma": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/engine-oniguruma/-/engine-oniguruma-2.5.0.tgz", - "integrity": "sha512-pGd1wRATzbo/uatrCIILlAdFVKdxImWJGQ5rFiB5VZi2ve5xj3Ax9jny8QvkaV93btQEwR/rSz5ERFpC5mKNIw==", - "license": "MIT", - "dependencies": { - "@shikijs/types": "2.5.0", - "@shikijs/vscode-textmate": "^10.0.2" - } - }, - "node_modules/@shikijs/langs": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/langs/-/langs-2.5.0.tgz", - "integrity": "sha512-Qfrrt5OsNH5R+5tJ/3uYBBZv3SuGmnRPejV9IlIbFH3HTGLDlkqgHymAlzklVmKBjAaVmkPkyikAV/sQ1wSL+w==", - "license": "MIT", - "dependencies": { - "@shikijs/types": "2.5.0" - } - }, - "node_modules/@shikijs/themes": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/themes/-/themes-2.5.0.tgz", - "integrity": "sha512-wGrk+R8tJnO0VMzmUExHR+QdSaPUl/NKs+a4cQQRWyoc3YFbUzuLEi/KWK1hj+8BfHRKm2jNhhJck1dfstJpiw==", - "license": "MIT", - "dependencies": { - "@shikijs/types": "2.5.0" - } - }, - "node_modules/@shikijs/transformers": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/transformers/-/transformers-2.5.0.tgz", - "integrity": "sha512-SI494W5X60CaUwgi8u4q4m4s3YAFSxln3tzNjOSYqq54wlVgz0/NbbXEb3mdLbqMBztcmS7bVTaEd2w0qMmfeg==", - "license": "MIT", - "dependencies": { - "@shikijs/core": "2.5.0", - "@shikijs/types": "2.5.0" - } - }, - "node_modules/@shikijs/types": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/@shikijs/types/-/types-2.5.0.tgz", - "integrity": "sha512-ygl5yhxki9ZLNuNpPitBWvcy9fsSKKaRuO4BAlMyagszQidxcpLAr0qiW/q43DtSIDxO6hEbtYLiFZNXO/hdGw==", - "license": "MIT", - "dependencies": { - "@shikijs/vscode-textmate": "^10.0.2", - "@types/hast": "^3.0.4" - } - }, - "node_modules/@shikijs/vscode-textmate": { - "version": "10.0.2", - "resolved": "https://registry.npmjs.org/@shikijs/vscode-textmate/-/vscode-textmate-10.0.2.tgz", - "integrity": "sha512-83yeghZ2xxin3Nj8z1NMd/NCuca+gsYXswywDy5bHvwlWL8tpTQmzGeUuHd9FC3E/SBEMvzJRwWEOz5gGes9Qg==", - "license": "MIT" - }, - "node_modules/@sindresorhus/merge-streams": { - "version": "4.0.0", - "resolved": "https://registry.npmjs.org/@sindresorhus/merge-streams/-/merge-streams-4.0.0.tgz", - "integrity": "sha512-tlqY9xq5ukxTUZBmoOp+m61cqwQD5pHJtFY3Mn8CA8ps6yghLH/Hw8UPdqg4OLmFW3IFlcXnQNmo/dh8HzXYIQ==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/@types/estree": { - "version": "1.0.8", - "resolved": "https://registry.npmjs.org/@types/estree/-/estree-1.0.8.tgz", - "integrity": "sha512-dWHzHa2WqEXI/O1E9OjrocMTKJl2mSrEolh1Iomrv6U+JuNwaHXsXx9bLu5gG7BUWFIN0skIQJQ/L1rIex4X6w==", - "license": "MIT" - }, - "node_modules/@types/hast": { - "version": "3.0.4", - "resolved": "https://registry.npmjs.org/@types/hast/-/hast-3.0.4.tgz", - "integrity": "sha512-WPs+bbQw5aCj+x6laNGWLH3wviHtoCv/P3+otBhbOhJgG8qtpdAMlTCxLtsTWA7LH1Oh/bFCHsBn0TPS5m30EQ==", - "license": "MIT", - "dependencies": { - "@types/unist": "*" - } - }, - "node_modules/@types/linkify-it": { - "version": "5.0.0", - "resolved": "https://registry.npmjs.org/@types/linkify-it/-/linkify-it-5.0.0.tgz", - "integrity": "sha512-sVDA58zAw4eWAffKOaQH5/5j3XeayukzDk+ewSsnv3p4yJEZHCCzMDiZM8e0OUrRvmpGZ85jf4yDHkHsgBNr9Q==", - "license": "MIT" - }, - "node_modules/@types/markdown-it": { - "version": "14.1.2", - "resolved": "https://registry.npmjs.org/@types/markdown-it/-/markdown-it-14.1.2.tgz", - "integrity": "sha512-promo4eFwuiW+TfGxhi+0x3czqTYJkG8qB17ZUJiVF10Xm7NLVRSLUsfRTU/6h1e24VvRnXCx+hG7li58lkzog==", - "license": "MIT", - "dependencies": { - "@types/linkify-it": "^5", - "@types/mdurl": "^2" - } - }, - "node_modules/@types/mdast": { - "version": "4.0.4", - "resolved": "https://registry.npmjs.org/@types/mdast/-/mdast-4.0.4.tgz", - "integrity": "sha512-kGaNbPh1k7AFzgpud/gMdvIm5xuECykRR+JnWKQno9TAXVa6WIVCGTPvYGekIDL4uwCZQSYbUxNBSb1aUo79oA==", - "license": "MIT", - "dependencies": { - "@types/unist": "*" - } - }, - "node_modules/@types/mdurl": { - "version": "2.0.0", - "resolved": "https://registry.npmjs.org/@types/mdurl/-/mdurl-2.0.0.tgz", - "integrity": "sha512-RGdgjQUZba5p6QEFAVx2OGb8rQDL/cPRG7GiedRzMcJ1tYnUANBncjbSB1NRGwbvjcPeikRABz2nshyPk1bhWg==", - "license": "MIT" - }, - "node_modules/@types/unist": { - "version": "3.0.3", - "resolved": "https://registry.npmjs.org/@types/unist/-/unist-3.0.3.tgz", - "integrity": "sha512-ko/gIFJRv177XgZsZcBwnqJN5x/Gien8qNOn0D5bQU/zAzVf9Zt3BlcUiLqhV9y4ARk0GbT3tnUiPNgnTXzc/Q==", - "license": "MIT" - }, - "node_modules/@types/web-bluetooth": { - "version": "0.0.21", - "resolved": "https://registry.npmjs.org/@types/web-bluetooth/-/web-bluetooth-0.0.21.tgz", - "integrity": "sha512-oIQLCGWtcFZy2JW77j9k8nHzAOpqMHLQejDA48XXMWH6tjCQHz5RCFz1bzsmROyL6PUm+LLnUiI4BCn221inxA==", - "license": "MIT" - }, - "node_modules/@ungap/structured-clone": { - "version": "1.3.0", - "resolved": "https://registry.npmjs.org/@ungap/structured-clone/-/structured-clone-1.3.0.tgz", - "integrity": "sha512-WmoN8qaIAo7WTYWbAZuG8PYEhn5fkz7dZrqTBZ7dtt//lL2Gwms1IcnQ5yHqjDfX8Ft5j4YzDM23f87zBfDe9g==", - "license": "ISC" - }, - "node_modules/@vitejs/plugin-vue": { - "version": "5.2.4", - "resolved": "https://registry.npmjs.org/@vitejs/plugin-vue/-/plugin-vue-5.2.4.tgz", - "integrity": "sha512-7Yx/SXSOcQq5HiiV3orevHUFn+pmMB4cgbEkDYgnkUWb0WfeQ/wa2yFv6D5ICiCQOVpjA7vYDXrC7AGO8yjDHA==", - "license": "MIT", - "engines": { - "node": "^18.0.0 || >=20.0.0" - }, - "peerDependencies": { - "vite": "^5.0.0 || ^6.0.0", - "vue": "^3.2.25" - } - }, - "node_modules/@vue/compiler-core": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/compiler-core/-/compiler-core-3.5.17.tgz", - "integrity": "sha512-Xe+AittLbAyV0pabcN7cP7/BenRBNcteM4aSDCtRvGw0d9OL+HG1u/XHLY/kt1q4fyMeZYXyIYrsHuPSiDPosA==", - "license": "MIT", - "dependencies": { - "@babel/parser": "^7.27.5", - "@vue/shared": "3.5.17", - "entities": "^4.5.0", - "estree-walker": "^2.0.2", - "source-map-js": "^1.2.1" - } - }, - "node_modules/@vue/compiler-core/node_modules/entities": { - "version": "4.5.0", - "resolved": "https://registry.npmjs.org/entities/-/entities-4.5.0.tgz", - "integrity": "sha512-V0hjH4dGPh9Ao5p0MoRY6BVqtwCjhz6vI5LT8AJ55H+4g9/4vbHx1I54fS0XuclLhDHArPQCiMjDxjaL8fPxhw==", - "license": "BSD-2-Clause", - "engines": { - "node": ">=0.12" - }, - "funding": { - "url": "https://github.com/fb55/entities?sponsor=1" - } - }, - "node_modules/@vue/compiler-dom": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/compiler-dom/-/compiler-dom-3.5.17.tgz", - "integrity": "sha512-+2UgfLKoaNLhgfhV5Ihnk6wB4ljyW1/7wUIog2puUqajiC29Lp5R/IKDdkebh9jTbTogTbsgB+OY9cEWzG95JQ==", - "license": "MIT", - "dependencies": { - "@vue/compiler-core": "3.5.17", - "@vue/shared": "3.5.17" - } - }, - "node_modules/@vue/compiler-sfc": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/compiler-sfc/-/compiler-sfc-3.5.17.tgz", - "integrity": "sha512-rQQxbRJMgTqwRugtjw0cnyQv9cP4/4BxWfTdRBkqsTfLOHWykLzbOc3C4GGzAmdMDxhzU/1Ija5bTjMVrddqww==", - "license": "MIT", - "dependencies": { - "@babel/parser": "^7.27.5", - "@vue/compiler-core": "3.5.17", - "@vue/compiler-dom": "3.5.17", - "@vue/compiler-ssr": "3.5.17", - "@vue/shared": "3.5.17", - "estree-walker": "^2.0.2", - "magic-string": "^0.30.17", - "postcss": "^8.5.6", - "source-map-js": "^1.2.1" - } - }, - "node_modules/@vue/compiler-ssr": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/compiler-ssr/-/compiler-ssr-3.5.17.tgz", - "integrity": "sha512-hkDbA0Q20ZzGgpj5uZjb9rBzQtIHLS78mMilwrlpWk2Ep37DYntUz0PonQ6kr113vfOEdM+zTBuJDaceNIW0tQ==", - "license": "MIT", - "dependencies": { - "@vue/compiler-dom": "3.5.17", - "@vue/shared": "3.5.17" - } - }, - "node_modules/@vue/devtools-api": { - "version": "7.7.7", - "resolved": "https://registry.npmjs.org/@vue/devtools-api/-/devtools-api-7.7.7.tgz", - "integrity": "sha512-lwOnNBH2e7x1fIIbVT7yF5D+YWhqELm55/4ZKf45R9T8r9dE2AIOy8HKjfqzGsoTHFbWbr337O4E0A0QADnjBg==", - "license": "MIT", - "dependencies": { - "@vue/devtools-kit": "^7.7.7" - } - }, - "node_modules/@vue/devtools-kit": { - "version": "7.7.7", - "resolved": "https://registry.npmjs.org/@vue/devtools-kit/-/devtools-kit-7.7.7.tgz", - "integrity": "sha512-wgoZtxcTta65cnZ1Q6MbAfePVFxfM+gq0saaeytoph7nEa7yMXoi6sCPy4ufO111B9msnw0VOWjPEFCXuAKRHA==", - "license": "MIT", - "dependencies": { - "@vue/devtools-shared": "^7.7.7", - "birpc": "^2.3.0", - "hookable": "^5.5.3", - "mitt": "^3.0.1", - "perfect-debounce": "^1.0.0", - "speakingurl": "^14.0.1", - "superjson": "^2.2.2" - } - }, - "node_modules/@vue/devtools-shared": { - "version": "7.7.7", - "resolved": "https://registry.npmjs.org/@vue/devtools-shared/-/devtools-shared-7.7.7.tgz", - "integrity": "sha512-+udSj47aRl5aKb0memBvcUG9koarqnxNM5yjuREvqwK6T3ap4mn3Zqqc17QrBFTqSMjr3HK1cvStEZpMDpfdyw==", - "license": "MIT", - "dependencies": { - "rfdc": "^1.4.1" - } - }, - "node_modules/@vue/reactivity": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/reactivity/-/reactivity-3.5.17.tgz", - "integrity": "sha512-l/rmw2STIscWi7SNJp708FK4Kofs97zc/5aEPQh4bOsReD/8ICuBcEmS7KGwDj5ODQLYWVN2lNibKJL1z5b+Lw==", - "license": "MIT", - "dependencies": { - "@vue/shared": "3.5.17" - } - }, - "node_modules/@vue/runtime-core": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/runtime-core/-/runtime-core-3.5.17.tgz", - "integrity": "sha512-QQLXa20dHg1R0ri4bjKeGFKEkJA7MMBxrKo2G+gJikmumRS7PTD4BOU9FKrDQWMKowz7frJJGqBffYMgQYS96Q==", - "license": "MIT", - "dependencies": { - "@vue/reactivity": "3.5.17", - "@vue/shared": "3.5.17" - } - }, - "node_modules/@vue/runtime-dom": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/runtime-dom/-/runtime-dom-3.5.17.tgz", - "integrity": "sha512-8El0M60TcwZ1QMz4/os2MdlQECgGoVHPuLnQBU3m9h3gdNRW9xRmI8iLS4t/22OQlOE6aJvNNlBiCzPHur4H9g==", - "license": "MIT", - "dependencies": { - "@vue/reactivity": "3.5.17", - "@vue/runtime-core": "3.5.17", - "@vue/shared": "3.5.17", - "csstype": "^3.1.3" - } - }, - "node_modules/@vue/server-renderer": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/server-renderer/-/server-renderer-3.5.17.tgz", - "integrity": "sha512-BOHhm8HalujY6lmC3DbqF6uXN/K00uWiEeF22LfEsm9Q93XeJ/plHTepGwf6tqFcF7GA5oGSSAAUock3VvzaCA==", - "license": "MIT", - "dependencies": { - "@vue/compiler-ssr": "3.5.17", - "@vue/shared": "3.5.17" - }, - "peerDependencies": { - "vue": "3.5.17" - } - }, - "node_modules/@vue/shared": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/@vue/shared/-/shared-3.5.17.tgz", - "integrity": "sha512-CabR+UN630VnsJO/jHWYBC1YVXyMq94KKp6iF5MQgZJs5I8cmjw6oVMO1oDbtBkENSHSSn/UadWlW/OAgdmKrg==", - "license": "MIT" - }, - "node_modules/@vueuse/core": { - "version": "12.8.2", - "resolved": "https://registry.npmjs.org/@vueuse/core/-/core-12.8.2.tgz", - "integrity": "sha512-HbvCmZdzAu3VGi/pWYm5Ut+Kd9mn1ZHnn4L5G8kOQTPs/IwIAmJoBrmYk2ckLArgMXZj0AW3n5CAejLUO+PhdQ==", - "license": "MIT", - "dependencies": { - "@types/web-bluetooth": "^0.0.21", - "@vueuse/metadata": "12.8.2", - "@vueuse/shared": "12.8.2", - "vue": "^3.5.13" - }, - "funding": { - "url": "https://github.com/sponsors/antfu" - } - }, - "node_modules/@vueuse/integrations": { - "version": "12.8.2", - "resolved": "https://registry.npmjs.org/@vueuse/integrations/-/integrations-12.8.2.tgz", - "integrity": "sha512-fbGYivgK5uBTRt7p5F3zy6VrETlV9RtZjBqd1/HxGdjdckBgBM4ugP8LHpjolqTj14TXTxSK1ZfgPbHYyGuH7g==", - "license": "MIT", - "dependencies": { - "@vueuse/core": "12.8.2", - "@vueuse/shared": "12.8.2", - "vue": "^3.5.13" - }, - "funding": { - "url": "https://github.com/sponsors/antfu" - }, - "peerDependencies": { - "async-validator": "^4", - "axios": "^1", - "change-case": "^5", - "drauu": "^0.4", - "focus-trap": "^7", - "fuse.js": "^7", - "idb-keyval": "^6", - "jwt-decode": "^4", - "nprogress": "^0.2", - "qrcode": "^1.5", - "sortablejs": "^1", - "universal-cookie": "^7" - }, - "peerDependenciesMeta": { - "async-validator": { - "optional": true - }, - "axios": { - "optional": true - }, - "change-case": { - "optional": true - }, - "drauu": { - "optional": true - }, - "focus-trap": { - "optional": true - }, - "fuse.js": { - "optional": true - }, - "idb-keyval": { - "optional": true - }, - "jwt-decode": { - "optional": true - }, - "nprogress": { - "optional": true - }, - "qrcode": { - "optional": true - }, - "sortablejs": { - "optional": true - }, - "universal-cookie": { - "optional": true - } - } - }, - "node_modules/@vueuse/metadata": { - "version": "12.8.2", - "resolved": "https://registry.npmjs.org/@vueuse/metadata/-/metadata-12.8.2.tgz", - "integrity": "sha512-rAyLGEuoBJ/Il5AmFHiziCPdQzRt88VxR+Y/A/QhJ1EWtWqPBBAxTAFaSkviwEuOEZNtW8pvkPgoCZQ+HxqW1A==", - "license": "MIT", - "funding": { - "url": "https://github.com/sponsors/antfu" - } - }, - "node_modules/@vueuse/shared": { - "version": "12.8.2", - "resolved": "https://registry.npmjs.org/@vueuse/shared/-/shared-12.8.2.tgz", - "integrity": "sha512-dznP38YzxZoNloI0qpEfpkms8knDtaoQ6Y/sfS0L7Yki4zh40LFHEhur0odJC6xTHG5dxWVPiUWBXn+wCG2s5w==", - "license": "MIT", - "dependencies": { - "vue": "^3.5.13" - }, - "funding": { - "url": "https://github.com/sponsors/antfu" - } - }, - "node_modules/@xmldom/xmldom": { - "version": "0.9.8", - "resolved": "https://registry.npmjs.org/@xmldom/xmldom/-/xmldom-0.9.8.tgz", - "integrity": "sha512-p96FSY54r+WJ50FIOsCOjyj/wavs8921hG5+kVMmZgKcvIKxMXHTrjNJvRgWa/zuX3B6t2lijLNFaOyuxUH+2A==", - "license": "MIT", - "engines": { - "node": ">=14.6" - } - }, - "node_modules/algoliasearch": { - "version": "5.32.0", - "resolved": "https://registry.npmjs.org/algoliasearch/-/algoliasearch-5.32.0.tgz", - "integrity": "sha512-84xBncKNPBK8Ae89F65+SyVcOihrIbm/3N7to+GpRBHEUXGjA3ydWTMpcRW6jmFzkBQ/eqYy/y+J+NBpJWYjBg==", - "license": "MIT", - "peer": true, - "dependencies": { - "@algolia/client-abtesting": "5.32.0", - "@algolia/client-analytics": "5.32.0", - "@algolia/client-common": "5.32.0", - "@algolia/client-insights": "5.32.0", - "@algolia/client-personalization": "5.32.0", - "@algolia/client-query-suggestions": "5.32.0", - "@algolia/client-search": "5.32.0", - "@algolia/ingestion": "1.32.0", - "@algolia/monitoring": "1.32.0", - "@algolia/recommend": "5.32.0", - "@algolia/requester-browser-xhr": "5.32.0", - "@algolia/requester-fetch": "5.32.0", - "@algolia/requester-node-http": "5.32.0" - }, - "engines": { - "node": ">= 14.0.0" - } - }, - "node_modules/ansi-colors": { - "version": "4.1.3", - "resolved": "https://registry.npmjs.org/ansi-colors/-/ansi-colors-4.1.3.tgz", - "integrity": "sha512-/6w/C21Pm1A7aZitlI5Ni/2J6FFQN8i1Cvz3kHABAAbw93v/NlvKdVOqz7CCWz/3iv/JplRSEEZ83XION15ovw==", - "license": "MIT", - "engines": { - "node": ">=6" - } - }, - "node_modules/argparse": { - "version": "2.0.1", - "resolved": "https://registry.npmjs.org/argparse/-/argparse-2.0.1.tgz", - "integrity": "sha512-8+9WqebbFzpX9OR+Wa6O29asIogeRMzcGtAINdpMHHyAg10f05aSFVBbcEqGf/PXw1EjAZ+q2/bEBg3DvurK3Q==", - "license": "Python-2.0" - }, - "node_modules/birpc": { - "version": "2.4.0", - "resolved": "https://registry.npmjs.org/birpc/-/birpc-2.4.0.tgz", - "integrity": "sha512-5IdNxTyhXHv2UlgnPHQ0h+5ypVmkrYHzL8QT+DwFZ//2N/oNV8Ch+BCRmTJ3x6/z9Axo/cXYBc9eprsUVK/Jsg==", - "license": "MIT", - "funding": { - "url": "https://github.com/sponsors/antfu" - } - }, - "node_modules/boolbase": { - "version": "1.0.0", - "resolved": "https://registry.npmjs.org/boolbase/-/boolbase-1.0.0.tgz", - "integrity": "sha512-JZOSA7Mo9sNGB8+UjSgzdLtokWAky1zbztM3WRLCbZ70/3cTANmQmOdR7y2g+J0e2WXywy1yS468tY+IruqEww==", - "license": "ISC" - }, - "node_modules/bundle-name": { - "version": "4.1.0", - "resolved": "https://registry.npmjs.org/bundle-name/-/bundle-name-4.1.0.tgz", - "integrity": "sha512-tjwM5exMg6BGRI+kNmTntNsvdZS1X8BFYS6tnJ2hdH0kVxM6/eVZ2xy+FqStSWvYmtfFMDLIxurorHwDKfDz5Q==", - "license": "MIT", - "dependencies": { - "run-applescript": "^7.0.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/ccount": { - "version": "2.0.1", - "resolved": "https://registry.npmjs.org/ccount/-/ccount-2.0.1.tgz", - "integrity": "sha512-eyrF0jiFpY+3drT6383f1qhkbGsLSifNAjA61IUjZjmLCWjItY6LB9ft9YhoDgwfmclB2zhu51Lc7+95b8NRAg==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/character-entities-html4": { - "version": "2.1.0", - "resolved": "https://registry.npmjs.org/character-entities-html4/-/character-entities-html4-2.1.0.tgz", - "integrity": "sha512-1v7fgQRj6hnSwFpq1Eu0ynr/CDEw0rXo2B61qXrLNdHZmPKgb7fqS1a2JwF0rISo9q77jDI8VMEHoApn8qDoZA==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/character-entities-legacy": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/character-entities-legacy/-/character-entities-legacy-3.0.0.tgz", - "integrity": "sha512-RpPp0asT/6ufRm//AJVwpViZbGM/MkjQFxJccQRHmISF/22NBtsHqAWmL+/pmkPWoIUJdWyeVleTl1wydHATVQ==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/cheerio": { - "version": "1.0.0-rc.10", - "resolved": "https://registry.npmjs.org/cheerio/-/cheerio-1.0.0-rc.10.tgz", - "integrity": "sha512-g0J0q/O6mW8z5zxQ3A8E8J1hUgp4SMOvEoW/x84OwyHKe/Zccz83PVT4y5Crcr530FV6NgmKI1qvGTKVl9XXVw==", - "license": "MIT", - "dependencies": { - "cheerio-select": "^1.5.0", - "dom-serializer": "^1.3.2", - "domhandler": "^4.2.0", - "htmlparser2": "^6.1.0", - "parse5": "^6.0.1", - "parse5-htmlparser2-tree-adapter": "^6.0.1", - "tslib": "^2.2.0" - }, - "engines": { - "node": ">= 6" - }, - "funding": { - "url": "https://github.com/cheeriojs/cheerio?sponsor=1" - } - }, - "node_modules/cheerio-select": { - "version": "1.6.0", - "resolved": "https://registry.npmjs.org/cheerio-select/-/cheerio-select-1.6.0.tgz", - "integrity": "sha512-eq0GdBvxVFbqWgmCm7M3XGs1I8oLy/nExUnh6oLqmBditPO9AqQJrkslDpMun/hZ0yyTs8L0m85OHp4ho6Qm9g==", - "license": "BSD-2-Clause", - "dependencies": { - "css-select": "^4.3.0", - "css-what": "^6.0.1", - "domelementtype": "^2.2.0", - "domhandler": "^4.3.1", - "domutils": "^2.8.0" - }, - "funding": { - "url": "https://github.com/sponsors/fb55" - } - }, - "node_modules/comma-separated-tokens": { - "version": "2.0.3", - "resolved": "https://registry.npmjs.org/comma-separated-tokens/-/comma-separated-tokens-2.0.3.tgz", - "integrity": "sha512-Fu4hJdvzeylCfQPp9SGWidpzrMs7tTrlu6Vb8XGaRGck8QSNZJJp538Wrb60Lax4fPwR64ViY468OIUTbRlGZg==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/commander": { - "version": "6.2.1", - "resolved": "https://registry.npmjs.org/commander/-/commander-6.2.1.tgz", - "integrity": "sha512-U7VdrJFnJgo4xjrHpTzu0yrHPGImdsmD95ZlgYSEajAn2JKzDhDTPG9kBTefmObL2w/ngeZnilk+OV9CG3d7UA==", - "license": "MIT", - "engines": { - "node": ">= 6" - } - }, - "node_modules/copy-anything": { - "version": "3.0.5", - "resolved": "https://registry.npmjs.org/copy-anything/-/copy-anything-3.0.5.tgz", - "integrity": "sha512-yCEafptTtb4bk7GLEQoM8KVJpxAfdBJYaXyzQEgQQQgYrZiDp8SJmGKlYza6CYjEDNstAdNdKA3UuoULlEbS6w==", - "license": "MIT", - "dependencies": { - "is-what": "^4.1.8" - }, - "engines": { - "node": ">=12.13" - }, - "funding": { - "url": "https://github.com/sponsors/mesqueeb" - } - }, - "node_modules/cross-spawn": { - "version": "7.0.6", - "resolved": "https://registry.npmjs.org/cross-spawn/-/cross-spawn-7.0.6.tgz", - "integrity": "sha512-uV2QOWP2nWzsy2aMp8aRibhi9dlzF5Hgh5SHaB9OiTGEyDTiJJyx0uy51QXdyWbtAHNua4XJzUKca3OzKUd3vA==", - "license": "MIT", - "dependencies": { - "path-key": "^3.1.0", - "shebang-command": "^2.0.0", - "which": "^2.0.1" - }, - "engines": { - "node": ">= 8" - } - }, - "node_modules/css-select": { - "version": "4.3.0", - "resolved": "https://registry.npmjs.org/css-select/-/css-select-4.3.0.tgz", - "integrity": "sha512-wPpOYtnsVontu2mODhA19JrqWxNsfdatRKd64kmpRbQgh1KtItko5sTnEpPdpSaJszTOhEMlF/RPz28qj4HqhQ==", - "license": "BSD-2-Clause", - "dependencies": { - "boolbase": "^1.0.0", - "css-what": "^6.0.1", - "domhandler": "^4.3.1", - "domutils": "^2.8.0", - "nth-check": "^2.0.1" - }, - "funding": { - "url": "https://github.com/sponsors/fb55" - } - }, - "node_modules/css-what": { - "version": "6.2.2", - "resolved": "https://registry.npmjs.org/css-what/-/css-what-6.2.2.tgz", - "integrity": "sha512-u/O3vwbptzhMs3L1fQE82ZSLHQQfto5gyZzwteVIEyeaY5Fc7R4dapF/BvRoSYFeqfBk4m0V1Vafq5Pjv25wvA==", - "license": "BSD-2-Clause", - "engines": { - "node": ">= 6" - }, - "funding": { - "url": "https://github.com/sponsors/fb55" - } - }, - "node_modules/csstype": { - "version": "3.1.3", - "resolved": "https://registry.npmjs.org/csstype/-/csstype-3.1.3.tgz", - "integrity": "sha512-M1uQkMl8rQK/szD0LNhtqxIPLpimGm8sOBwU7lLnCpSbTyY3yeU1Vc7l4KT5zT4s/yOxHH5O7tIuuLOCnLADRw==", - "license": "MIT" - }, - "node_modules/default-browser": { - "version": "5.2.1", - "resolved": "https://registry.npmjs.org/default-browser/-/default-browser-5.2.1.tgz", - "integrity": "sha512-WY/3TUME0x3KPYdRRxEJJvXRHV4PyPoUsxtZa78lwItwRQRHhd2U9xOscaT/YTf8uCXIAjeJOFBVEh/7FtD8Xg==", - "license": "MIT", - "dependencies": { - "bundle-name": "^4.1.0", - "default-browser-id": "^5.0.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/default-browser-id": { - "version": "5.0.0", - "resolved": "https://registry.npmjs.org/default-browser-id/-/default-browser-id-5.0.0.tgz", - "integrity": "sha512-A6p/pu/6fyBcA1TRz/GqWYPViplrftcW2gZC9q79ngNCKAeR/X3gcEdXQHl4KNXV+3wgIJ1CPkJQ3IHM6lcsyA==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/define-lazy-prop": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/define-lazy-prop/-/define-lazy-prop-3.0.0.tgz", - "integrity": "sha512-N+MeXYoqr3pOgn8xfyRPREN7gHakLYjhsHhWGT3fWAiL4IkAt0iDw14QiiEm2bE30c5XX5q0FtAA3CK5f9/BUg==", - "license": "MIT", - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/dequal": { - "version": "2.0.3", - "resolved": "https://registry.npmjs.org/dequal/-/dequal-2.0.3.tgz", - "integrity": "sha512-0je+qPKHEMohvfRTCEo3CrPG6cAzAYgmzKyxRiYSSDkS6eGJdyVJm7WaYA5ECaAD9wLB2T4EEeymA5aFVcYXCA==", - "license": "MIT", - "engines": { - "node": ">=6" - } - }, - "node_modules/devlop": { - "version": "1.1.0", - "resolved": "https://registry.npmjs.org/devlop/-/devlop-1.1.0.tgz", - "integrity": "sha512-RWmIqhcFf1lRYBvNmr7qTNuyCt/7/ns2jbpp1+PalgE/rDQcBT0fioSMUpJ93irlUhC5hrg4cYqe6U+0ImW0rA==", - "license": "MIT", - "dependencies": { - "dequal": "^2.0.0" - }, - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/dom-serializer": { - "version": "1.4.1", - "resolved": "https://registry.npmjs.org/dom-serializer/-/dom-serializer-1.4.1.tgz", - "integrity": "sha512-VHwB3KfrcOOkelEG2ZOfxqLZdfkil8PtJi4P8N2MMXucZq2yLp75ClViUlOVwyoHEDjYU433Aq+5zWP61+RGag==", - "license": "MIT", - "dependencies": { - "domelementtype": "^2.0.1", - "domhandler": "^4.2.0", - "entities": "^2.0.0" - }, - "funding": { - "url": "https://github.com/cheeriojs/dom-serializer?sponsor=1" - } - }, - "node_modules/dom-serializer/node_modules/entities": { - "version": "2.2.0", - "resolved": "https://registry.npmjs.org/entities/-/entities-2.2.0.tgz", - "integrity": "sha512-p92if5Nz619I0w+akJrLZH0MX0Pb5DX39XOwQTtXSdQQOaYH03S1uIQp4mhOZtAXrxq4ViO67YTiLBo2638o9A==", - "license": "BSD-2-Clause", - "funding": { - "url": "https://github.com/fb55/entities?sponsor=1" - } - }, - "node_modules/domelementtype": { - "version": "2.3.0", - "resolved": "https://registry.npmjs.org/domelementtype/-/domelementtype-2.3.0.tgz", - "integrity": "sha512-OLETBj6w0OsagBwdXnPdN0cnMfF9opN69co+7ZrbfPGrdpPVNBUj02spi6B1N7wChLQiPn4CSH/zJvXw56gmHw==", - "funding": [ - { - "type": "github", - "url": "https://github.com/sponsors/fb55" - } - ], - "license": "BSD-2-Clause" - }, - "node_modules/domhandler": { - "version": "4.3.1", - "resolved": "https://registry.npmjs.org/domhandler/-/domhandler-4.3.1.tgz", - "integrity": "sha512-GrwoxYN+uWlzO8uhUXRl0P+kHE4GtVPfYzVLcUxPL7KNdHKj66vvlhiweIHqYYXWlw+T8iLMp42Lm67ghw4WMQ==", - "license": "BSD-2-Clause", - "dependencies": { - "domelementtype": "^2.2.0" - }, - "engines": { - "node": ">= 4" - }, - "funding": { - "url": "https://github.com/fb55/domhandler?sponsor=1" - } - }, - "node_modules/domutils": { - "version": "2.8.0", - "resolved": "https://registry.npmjs.org/domutils/-/domutils-2.8.0.tgz", - "integrity": "sha512-w96Cjofp72M5IIhpjgobBimYEfoPjx1Vx0BSX9P30WBdZW2WIKU0T1Bd0kz2eNZ9ikjKgHbEyKx8BB6H1L3h3A==", - "license": "BSD-2-Clause", - "dependencies": { - "dom-serializer": "^1.0.1", - "domelementtype": "^2.2.0", - "domhandler": "^4.2.0" - }, - "funding": { - "url": "https://github.com/fb55/domutils?sponsor=1" - } - }, - "node_modules/emoji-regex-xs": { - "version": "1.0.0", - "resolved": "https://registry.npmjs.org/emoji-regex-xs/-/emoji-regex-xs-1.0.0.tgz", - "integrity": "sha512-LRlerrMYoIDrT6jgpeZ2YYl/L8EulRTt5hQcYjy5AInh7HWXKimpqx68aknBFpGL2+/IcogTcaydJEgaTmOpDg==", - "license": "MIT" - }, - "node_modules/entities": { - "version": "3.0.1", - "resolved": "https://registry.npmjs.org/entities/-/entities-3.0.1.tgz", - "integrity": "sha512-WiyBqoomrwMdFG1e0kqvASYfnlb0lp8M5o5Fw2OFq1hNZxxcNk8Ik0Xm7LxzBhuidnZB/UtBqVCgUz3kBOP51Q==", - "license": "BSD-2-Clause", - "engines": { - "node": ">=0.12" - }, - "funding": { - "url": "https://github.com/fb55/entities?sponsor=1" - } - }, - "node_modules/env-editor": { - "version": "1.1.0", - "resolved": "https://registry.npmjs.org/env-editor/-/env-editor-1.1.0.tgz", - "integrity": "sha512-7AXskzN6T7Q9TFcKAGJprUbpQa4i1VsAetO9rdBqbGMGlragTziBgWt4pVYJMBWHQlLoX0buy6WFikzPH4Qjpw==", - "license": "MIT", - "engines": { - "node": "^12.20.0 || ^14.13.1 || >=16.0.0" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/esbuild": { - "version": "0.21.5", - "resolved": "https://registry.npmjs.org/esbuild/-/esbuild-0.21.5.tgz", - "integrity": "sha512-mg3OPMV4hXywwpoDxu3Qda5xCKQi+vCTZq8S9J/EpkhB2HzKXq4SNFZE3+NK93JYxc8VMSep+lOUSC/RVKaBqw==", - "hasInstallScript": true, - "license": "MIT", - "bin": { - "esbuild": "bin/esbuild" - }, - "engines": { - "node": ">=12" - }, - "optionalDependencies": { - "@esbuild/aix-ppc64": "0.21.5", - "@esbuild/android-arm": "0.21.5", - "@esbuild/android-arm64": "0.21.5", - "@esbuild/android-x64": "0.21.5", - "@esbuild/darwin-arm64": "0.21.5", - "@esbuild/darwin-x64": "0.21.5", - "@esbuild/freebsd-arm64": "0.21.5", - "@esbuild/freebsd-x64": "0.21.5", - "@esbuild/linux-arm": "0.21.5", - "@esbuild/linux-arm64": "0.21.5", - "@esbuild/linux-ia32": "0.21.5", - "@esbuild/linux-loong64": "0.21.5", - "@esbuild/linux-mips64el": "0.21.5", - "@esbuild/linux-ppc64": "0.21.5", - "@esbuild/linux-riscv64": "0.21.5", - "@esbuild/linux-s390x": "0.21.5", - "@esbuild/linux-x64": "0.21.5", - "@esbuild/netbsd-x64": "0.21.5", - "@esbuild/openbsd-x64": "0.21.5", - "@esbuild/sunos-x64": "0.21.5", - "@esbuild/win32-arm64": "0.21.5", - "@esbuild/win32-ia32": "0.21.5", - "@esbuild/win32-x64": "0.21.5" - } - }, - "node_modules/escape-goat": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/escape-goat/-/escape-goat-3.0.0.tgz", - "integrity": "sha512-w3PwNZJwRxlp47QGzhuEBldEqVHHhh8/tIPcl6ecf2Bou99cdAt0knihBV0Ecc7CGxYduXVBDheH1K2oADRlvw==", - "license": "MIT", - "engines": { - "node": ">=10" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/esm": { - "version": "3.2.25", - "resolved": "https://registry.npmjs.org/esm/-/esm-3.2.25.tgz", - "integrity": "sha512-U1suiZ2oDVWv4zPO56S0NcR5QriEahGtdN2OR6FiOG4WJvcjBVFB0qI4+eKoWFH483PKGuLuu6V8Z4T5g63UVA==", - "license": "MIT", - "engines": { - "node": ">=6" - } - }, - "node_modules/estree-walker": { - "version": "2.0.2", - "resolved": "https://registry.npmjs.org/estree-walker/-/estree-walker-2.0.2.tgz", - "integrity": "sha512-Rfkk/Mp/DL7JVje3u18FxFujQlTNR2q6QfMSMB7AvCBx91NGj/ba3kCfza0f6dVDbw7YlRf/nDrn7pQrCCyQ/w==", - "license": "MIT" - }, - "node_modules/execa": { - "version": "9.6.0", - "resolved": "https://registry.npmjs.org/execa/-/execa-9.6.0.tgz", - "integrity": "sha512-jpWzZ1ZhwUmeWRhS7Qv3mhpOhLfwI+uAX4e5fOcXqwMR7EcJ0pj2kV1CVzHVMX/LphnKWD3LObjZCoJ71lKpHw==", - "license": "MIT", - "dependencies": { - "@sindresorhus/merge-streams": "^4.0.0", - "cross-spawn": "^7.0.6", - "figures": "^6.1.0", - "get-stream": "^9.0.0", - "human-signals": "^8.0.1", - "is-plain-obj": "^4.1.0", - "is-stream": "^4.0.1", - "npm-run-path": "^6.0.0", - "pretty-ms": "^9.2.0", - "signal-exit": "^4.1.0", - "strip-final-newline": "^4.0.0", - "yoctocolors": "^2.1.1" - }, - "engines": { - "node": "^18.19.0 || >=20.5.0" - }, - "funding": { - "url": "https://github.com/sindresorhus/execa?sponsor=1" - } - }, - "node_modules/figures": { - "version": "6.1.0", - "resolved": "https://registry.npmjs.org/figures/-/figures-6.1.0.tgz", - "integrity": "sha512-d+l3qxjSesT4V7v2fh+QnmFnUWv9lSpjarhShNTgBOfA0ttejbQUAlHLitbjkoRiDulW0OPoQPYIGhIC8ohejg==", - "license": "MIT", - "dependencies": { - "is-unicode-supported": "^2.0.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/focus-trap": { - "version": "7.6.5", - "resolved": "https://registry.npmjs.org/focus-trap/-/focus-trap-7.6.5.tgz", - "integrity": "sha512-7Ke1jyybbbPZyZXFxEftUtxFGLMpE2n6A+z//m4CRDlj0hW+o3iYSmh8nFlYMurOiJVDmJRilUQtJr08KfIxlg==", - "license": "MIT", - "peer": true, - "dependencies": { - "tabbable": "^6.2.0" - } - }, - "node_modules/fsevents": { - "version": "2.3.3", - "resolved": "https://registry.npmjs.org/fsevents/-/fsevents-2.3.3.tgz", - "integrity": "sha512-5xoDfX+fL7faATnagmWPpbFtwh/R77WmMMqqHGS65C3vvB0YHrgF+B1YmZ3441tMj5n63k0212XNoJwzlhffQw==", - "hasInstallScript": true, - "license": "MIT", - "optional": true, - "os": [ - "darwin" - ], - "engines": { - "node": "^8.16.0 || ^10.6.0 || >=11.0.0" - } - }, - "node_modules/get-stream": { - "version": "9.0.1", - "resolved": "https://registry.npmjs.org/get-stream/-/get-stream-9.0.1.tgz", - "integrity": "sha512-kVCxPF3vQM/N0B1PmoqVUqgHP+EeVjmZSQn+1oCRPxd2P21P2F19lIgbR3HBosbB1PUhOAoctJnfEn2GbN2eZA==", - "license": "MIT", - "dependencies": { - "@sec-ant/readable-stream": "^0.4.1", - "is-stream": "^4.0.1" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/hast-util-to-html": { - "version": "9.0.5", - "resolved": "https://registry.npmjs.org/hast-util-to-html/-/hast-util-to-html-9.0.5.tgz", - "integrity": "sha512-OguPdidb+fbHQSU4Q4ZiLKnzWo8Wwsf5bZfbvu7//a9oTYoqD/fWpe96NuHkoS9h0ccGOTe0C4NGXdtS0iObOw==", - "license": "MIT", - "dependencies": { - "@types/hast": "^3.0.0", - "@types/unist": "^3.0.0", - "ccount": "^2.0.0", - "comma-separated-tokens": "^2.0.0", - "hast-util-whitespace": "^3.0.0", - "html-void-elements": "^3.0.0", - "mdast-util-to-hast": "^13.0.0", - "property-information": "^7.0.0", - "space-separated-tokens": "^2.0.0", - "stringify-entities": "^4.0.0", - "zwitch": "^2.0.4" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/hast-util-whitespace": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/hast-util-whitespace/-/hast-util-whitespace-3.0.0.tgz", - "integrity": "sha512-88JUN06ipLwsnv+dVn+OIYOvAuvBMy/Qoi6O7mQHxdPXpjy+Cd6xRkWwux7DKO+4sYILtLBRIKgsdpS2gQc7qw==", - "license": "MIT", - "dependencies": { - "@types/hast": "^3.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/hookable": { - "version": "5.5.3", - "resolved": "https://registry.npmjs.org/hookable/-/hookable-5.5.3.tgz", - "integrity": "sha512-Yc+BQe8SvoXH1643Qez1zqLRmbA5rCL+sSmk6TVos0LWVfNIB7PGncdlId77WzLGSIB5KaWgTaNTs2lNVEI6VQ==", - "license": "MIT" - }, - "node_modules/html-void-elements": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/html-void-elements/-/html-void-elements-3.0.0.tgz", - "integrity": "sha512-bEqo66MRXsUGxWHV5IP0PUiAWwoEjba4VCzg0LjFJBpchPaTfyfCKTG6bc5F8ucKec3q5y6qOdGyYTSBEvhCrg==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/htmlparser2": { - "version": "6.1.0", - "resolved": "https://registry.npmjs.org/htmlparser2/-/htmlparser2-6.1.0.tgz", - "integrity": "sha512-gyyPk6rgonLFEDGoeRgQNaEUvdJ4ktTmmUh/h2t7s+M8oPpIPxgNACWa+6ESR57kXstwqPiCut0V8NRpcwgU7A==", - "funding": [ - "https://github.com/fb55/htmlparser2?sponsor=1", - { - "type": "github", - "url": "https://github.com/sponsors/fb55" - } - ], - "license": "MIT", - "dependencies": { - "domelementtype": "^2.0.1", - "domhandler": "^4.0.0", - "domutils": "^2.5.2", - "entities": "^2.0.0" - } - }, - "node_modules/htmlparser2/node_modules/entities": { - "version": "2.2.0", - "resolved": "https://registry.npmjs.org/entities/-/entities-2.2.0.tgz", - "integrity": "sha512-p92if5Nz619I0w+akJrLZH0MX0Pb5DX39XOwQTtXSdQQOaYH03S1uIQp4mhOZtAXrxq4ViO67YTiLBo2638o9A==", - "license": "BSD-2-Clause", - "funding": { - "url": "https://github.com/fb55/entities?sponsor=1" - } - }, - "node_modules/human-signals": { - "version": "8.0.1", - "resolved": "https://registry.npmjs.org/human-signals/-/human-signals-8.0.1.tgz", - "integrity": "sha512-eKCa6bwnJhvxj14kZk5NCPc6Hb6BdsU9DZcOnmQKSnO1VKrfV0zCvtttPZUsBvjmNDn8rpcJfpwSYnHBjc95MQ==", - "license": "Apache-2.0", - "engines": { - "node": ">=18.18.0" - } - }, - "node_modules/is-docker": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/is-docker/-/is-docker-3.0.0.tgz", - "integrity": "sha512-eljcgEDlEns/7AXFosB5K/2nCM4P7FQPkGc/DWLy5rmFEWvZayGrik1d9/QIY5nJ4f9YsVvBkA6kJpHn9rISdQ==", - "license": "MIT", - "bin": { - "is-docker": "cli.js" - }, - "engines": { - "node": "^12.20.0 || ^14.13.1 || >=16.0.0" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/is-inside-container": { - "version": "1.0.0", - "resolved": "https://registry.npmjs.org/is-inside-container/-/is-inside-container-1.0.0.tgz", - "integrity": "sha512-KIYLCCJghfHZxqjYBE7rEy0OBuTd5xCHS7tHVgvCLkx7StIoaxwNW3hCALgEUjFfeRk+MG/Qxmp/vtETEF3tRA==", - "license": "MIT", - "dependencies": { - "is-docker": "^3.0.0" - }, - "bin": { - "is-inside-container": "cli.js" - }, - "engines": { - "node": ">=14.16" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/is-plain-obj": { - "version": "4.1.0", - "resolved": "https://registry.npmjs.org/is-plain-obj/-/is-plain-obj-4.1.0.tgz", - "integrity": "sha512-+Pgi+vMuUNkJyExiMBt5IlFoMyKnr5zhJ4Uspz58WOhBF5QoIZkFyNHIbBAtHwzVAgk5RtndVNsDRN61/mmDqg==", - "license": "MIT", - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/is-stream": { - "version": "4.0.1", - "resolved": "https://registry.npmjs.org/is-stream/-/is-stream-4.0.1.tgz", - "integrity": "sha512-Dnz92NInDqYckGEUJv689RbRiTSEHCQ7wOVeALbkOz999YpqT46yMRIGtSNl2iCL1waAZSx40+h59NV/EwzV/A==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/is-unicode-supported": { - "version": "2.1.0", - "resolved": "https://registry.npmjs.org/is-unicode-supported/-/is-unicode-supported-2.1.0.tgz", - "integrity": "sha512-mE00Gnza5EEB3Ds0HfMyllZzbBrmLOX3vfWoj9A9PEnTfratQ/BcaJOuMhnkhjXvb2+FkY3VuHqtAGpTPmglFQ==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/is-what": { - "version": "4.1.16", - "resolved": "https://registry.npmjs.org/is-what/-/is-what-4.1.16.tgz", - "integrity": "sha512-ZhMwEosbFJkA0YhFnNDgTM4ZxDRsS6HqTo7qsZM08fehyRYIYa0yHu5R6mgo1n/8MgaPBXiPimPD77baVFYg+A==", - "license": "MIT", - "engines": { - "node": ">=12.13" - }, - "funding": { - "url": "https://github.com/sponsors/mesqueeb" - } - }, - "node_modules/is-wsl": { - "version": "3.1.0", - "resolved": "https://registry.npmjs.org/is-wsl/-/is-wsl-3.1.0.tgz", - "integrity": "sha512-UcVfVfaK4Sc4m7X3dUSoHoozQGBEFeDC+zVo06t98xe8CzHSZZBekNXH+tu0NalHolcJ/QAGqS46Hef7QXBIMw==", - "license": "MIT", - "dependencies": { - "is-inside-container": "^1.0.0" - }, - "engines": { - "node": ">=16" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/isexe": { - "version": "2.0.0", - "resolved": "https://registry.npmjs.org/isexe/-/isexe-2.0.0.tgz", - "integrity": "sha512-RHxMLp9lnKHGHRng9QFhRCMbYAcVpn69smSGcq3f36xjgVVWThj4qqLbTLlq7Ssj8B+fIQ1EuCEGI2lKsyQeIw==", - "license": "ISC" - }, - "node_modules/juice": { - "version": "8.1.0", - "resolved": "https://registry.npmjs.org/juice/-/juice-8.1.0.tgz", - "integrity": "sha512-FLzurJrx5Iv1e7CfBSZH68dC04EEvXvvVvPYB7Vx1WAuhCp1ZPIMtqxc+WTWxVkpTIC2Ach/GAv0rQbtGf6YMA==", - "license": "MIT", - "dependencies": { - "cheerio": "1.0.0-rc.10", - "commander": "^6.1.0", - "mensch": "^0.3.4", - "slick": "^1.12.2", - "web-resource-inliner": "^6.0.1" - }, - "bin": { - "juice": "bin/juice" - }, - "engines": { - "node": ">=10.0.0" - } - }, - "node_modules/line-column-path": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/line-column-path/-/line-column-path-3.0.0.tgz", - "integrity": "sha512-Atocnm7Wr9nuvAn97yEPQa3pcQI5eLQGBz+m6iTb+CVw+IOzYB9MrYK7jI7BfC9ISnT4Fu0eiwhAScV//rp4Hw==", - "license": "MIT", - "dependencies": { - "type-fest": "^2.0.0" - }, - "engines": { - "node": "^12.20.0 || ^14.13.1 || >=16.0.0" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/linkify-it": { - "version": "4.0.1", - "resolved": "https://registry.npmjs.org/linkify-it/-/linkify-it-4.0.1.tgz", - "integrity": "sha512-C7bfi1UZmoj8+PQx22XyeXCuBlokoyWQL5pWSP+EI6nzRylyThouddufc2c1NDIcP9k5agmN9fLpA7VNJfIiqw==", - "license": "MIT", - "dependencies": { - "uc.micro": "^1.0.1" - } - }, - "node_modules/lite-youtube-embed": { - "version": "0.3.3", - "resolved": "https://registry.npmjs.org/lite-youtube-embed/-/lite-youtube-embed-0.3.3.tgz", - "integrity": "sha512-gFfVVnj6NRjxVfJKo3qoLtpi0v5mn3AcR4eKD45wrxQuxzveFJUb+7Cr6uV6n+DjO8X3p0UzPPquhGt0H/y+NA==", - "license": "Apache-2.0" - }, - "node_modules/magic-string": { - "version": "0.30.17", - "resolved": "https://registry.npmjs.org/magic-string/-/magic-string-0.30.17.tgz", - "integrity": "sha512-sNPKHvyjVf7gyjwS4xGTaW/mCnF8wnjtifKBEhxfZ7E/S8tQ0rssrwGNn6q8JH/ohItJfSQp9mBtQYuTlH5QnA==", - "license": "MIT", - "dependencies": { - "@jridgewell/sourcemap-codec": "^1.5.0" - } - }, - "node_modules/mark.js": { - "version": "8.11.1", - "resolved": "https://registry.npmjs.org/mark.js/-/mark.js-8.11.1.tgz", - "integrity": "sha512-1I+1qpDt4idfgLQG+BNWmrqku+7/2bi5nLf4YwF8y8zXvmfiTBY3PV3ZibfrjBueCByROpuBjLLFCajqkgYoLQ==", - "license": "MIT" - }, - "node_modules/markdown-it": { - "version": "13.0.2", - "resolved": "https://registry.npmjs.org/markdown-it/-/markdown-it-13.0.2.tgz", - "integrity": "sha512-FtwnEuuK+2yVU7goGn/MJ0WBZMM9ZPgU9spqlFs7/A/pDIUNSOQZhUgOqYCficIuR2QaFnrt8LHqBWsbTAoI5w==", - "license": "MIT", - "dependencies": { - "argparse": "^2.0.1", - "entities": "~3.0.1", - "linkify-it": "^4.0.1", - "mdurl": "^1.0.1", - "uc.micro": "^1.0.5" - }, - "bin": { - "markdown-it": "bin/markdown-it.js" - } - }, - "node_modules/markdown-it-container": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/markdown-it-container/-/markdown-it-container-3.0.0.tgz", - "integrity": "sha512-y6oKTq4BB9OQuY/KLfk/O3ysFhB3IMYoIWhGJEidXt1NQFocFK2sA2t0NYZAMyMShAGL6x5OPIbrmXPIqaN9rw==", - "license": "MIT" - }, - "node_modules/markdown-it-mathjax3": { - "version": "4.3.2", - "resolved": "https://registry.npmjs.org/markdown-it-mathjax3/-/markdown-it-mathjax3-4.3.2.tgz", - "integrity": "sha512-TX3GW5NjmupgFtMJGRauioMbbkGsOXAAt1DZ/rzzYmTHqzkO1rNAdiMD4NiruurToPApn2kYy76x02QN26qr2w==", - "license": "MIT", - "peer": true, - "dependencies": { - "juice": "^8.0.0", - "mathjax-full": "^3.2.0" - } - }, - "node_modules/mathjax-full": { - "version": "3.2.2", - "resolved": "https://registry.npmjs.org/mathjax-full/-/mathjax-full-3.2.2.tgz", - "integrity": "sha512-+LfG9Fik+OuI8SLwsiR02IVdjcnRCy5MufYLi0C3TdMT56L/pjB0alMVGgoWJF8pN9Rc7FESycZB9BMNWIid5w==", - "license": "Apache-2.0", - "dependencies": { - "esm": "^3.2.25", - "mhchemparser": "^4.1.0", - "mj-context-menu": "^0.6.1", - "speech-rule-engine": "^4.0.6" - } - }, - "node_modules/mdast-util-to-hast": { - "version": "13.2.1", - "resolved": "https://registry.npmjs.org/mdast-util-to-hast/-/mdast-util-to-hast-13.2.1.tgz", - "integrity": "sha512-cctsq2wp5vTsLIcaymblUriiTcZd0CwWtCbLvrOzYCDZoWyMNV8sZ7krj09FSnsiJi3WVsHLM4k6Dq/yaPyCXA==", - "license": "MIT", - "dependencies": { - "@types/hast": "^3.0.0", - "@types/mdast": "^4.0.0", - "@ungap/structured-clone": "^1.0.0", - "devlop": "^1.0.0", - "micromark-util-sanitize-uri": "^2.0.0", - "trim-lines": "^3.0.0", - "unist-util-position": "^5.0.0", - "unist-util-visit": "^5.0.0", - "vfile": "^6.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/mdurl": { - "version": "1.0.1", - "resolved": "https://registry.npmjs.org/mdurl/-/mdurl-1.0.1.tgz", - "integrity": "sha512-/sKlQJCBYVY9Ers9hqzKou4H6V5UWc/M59TH2dvkt+84itfnq7uFOMLpOiOS4ujvHP4etln18fmIxA5R5fll0g==", - "license": "MIT" - }, - "node_modules/medium-zoom": { - "version": "1.1.0", - "resolved": "https://registry.npmjs.org/medium-zoom/-/medium-zoom-1.1.0.tgz", - "integrity": "sha512-ewyDsp7k4InCUp3jRmwHBRFGyjBimKps/AJLjRSox+2q/2H4p/PNpQf+pwONWlJiOudkBXtbdmVbFjqyybfTmQ==", - "license": "MIT" - }, - "node_modules/mensch": { - "version": "0.3.4", - "resolved": "https://registry.npmjs.org/mensch/-/mensch-0.3.4.tgz", - "integrity": "sha512-IAeFvcOnV9V0Yk+bFhYR07O3yNina9ANIN5MoXBKYJ/RLYPurd2d0yw14MDhpr9/momp0WofT1bPUh3hkzdi/g==", - "license": "MIT" - }, - "node_modules/mhchemparser": { - "version": "4.2.1", - "resolved": "https://registry.npmjs.org/mhchemparser/-/mhchemparser-4.2.1.tgz", - "integrity": "sha512-kYmyrCirqJf3zZ9t/0wGgRZ4/ZJw//VwaRVGA75C4nhE60vtnIzhl9J9ndkX/h6hxSN7pjg/cE0VxbnNM+bnDQ==", - "license": "Apache-2.0" - }, - "node_modules/micromark-util-character": { - "version": "2.1.1", - "resolved": "https://registry.npmjs.org/micromark-util-character/-/micromark-util-character-2.1.1.tgz", - "integrity": "sha512-wv8tdUTJ3thSFFFJKtpYKOYiGP2+v96Hvk4Tu8KpCAsTMs6yi+nVmGh1syvSCsaxz45J6Jbw+9DD6g97+NV67Q==", - "funding": [ - { - "type": "GitHub Sponsors", - "url": "https://github.com/sponsors/unifiedjs" - }, - { - "type": "OpenCollective", - "url": "https://opencollective.com/unified" - } - ], - "license": "MIT", - "dependencies": { - "micromark-util-symbol": "^2.0.0", - "micromark-util-types": "^2.0.0" - } - }, - "node_modules/micromark-util-encode": { - "version": "2.0.1", - "resolved": "https://registry.npmjs.org/micromark-util-encode/-/micromark-util-encode-2.0.1.tgz", - "integrity": "sha512-c3cVx2y4KqUnwopcO9b/SCdo2O67LwJJ/UyqGfbigahfegL9myoEFoDYZgkT7f36T0bLrM9hZTAaAyH+PCAXjw==", - "funding": [ - { - "type": "GitHub Sponsors", - "url": "https://github.com/sponsors/unifiedjs" - }, - { - "type": "OpenCollective", - "url": "https://opencollective.com/unified" - } - ], - "license": "MIT" - }, - "node_modules/micromark-util-sanitize-uri": { - "version": "2.0.1", - "resolved": "https://registry.npmjs.org/micromark-util-sanitize-uri/-/micromark-util-sanitize-uri-2.0.1.tgz", - "integrity": "sha512-9N9IomZ/YuGGZZmQec1MbgxtlgougxTodVwDzzEouPKo3qFWvymFHWcnDi2vzV1ff6kas9ucW+o3yzJK9YB1AQ==", - "funding": [ - { - "type": "GitHub Sponsors", - "url": "https://github.com/sponsors/unifiedjs" - }, - { - "type": "OpenCollective", - "url": "https://opencollective.com/unified" - } - ], - "license": "MIT", - "dependencies": { - "micromark-util-character": "^2.0.0", - "micromark-util-encode": "^2.0.0", - "micromark-util-symbol": "^2.0.0" - } - }, - "node_modules/micromark-util-symbol": { - "version": "2.0.1", - "resolved": "https://registry.npmjs.org/micromark-util-symbol/-/micromark-util-symbol-2.0.1.tgz", - "integrity": "sha512-vs5t8Apaud9N28kgCrRUdEed4UJ+wWNvicHLPxCa9ENlYuAY31M0ETy5y1vA33YoNPDFTghEbnh6efaE8h4x0Q==", - "funding": [ - { - "type": "GitHub Sponsors", - "url": "https://github.com/sponsors/unifiedjs" - }, - { - "type": "OpenCollective", - "url": "https://opencollective.com/unified" - } - ], - "license": "MIT" - }, - "node_modules/micromark-util-types": { - "version": "2.0.2", - "resolved": "https://registry.npmjs.org/micromark-util-types/-/micromark-util-types-2.0.2.tgz", - "integrity": "sha512-Yw0ECSpJoViF1qTU4DC6NwtC4aWGt1EkzaQB8KPPyCRR8z9TWeV0HbEFGTO+ZY1wB22zmxnJqhPyTpOVCpeHTA==", - "funding": [ - { - "type": "GitHub Sponsors", - "url": "https://github.com/sponsors/unifiedjs" - }, - { - "type": "OpenCollective", - "url": "https://opencollective.com/unified" - } - ], - "license": "MIT" - }, - "node_modules/mime": { - "version": "2.6.0", - "resolved": "https://registry.npmjs.org/mime/-/mime-2.6.0.tgz", - "integrity": "sha512-USPkMeET31rOMiarsBNIHZKLGgvKc/LrjofAnBlOttf5ajRvqiRA8QsenbcooctK6d6Ts6aqZXBA+XbkKthiQg==", - "license": "MIT", - "bin": { - "mime": "cli.js" - }, - "engines": { - "node": ">=4.0.0" - } - }, - "node_modules/minisearch": { - "version": "7.1.2", - "resolved": "https://registry.npmjs.org/minisearch/-/minisearch-7.1.2.tgz", - "integrity": "sha512-R1Pd9eF+MD5JYDDSPAp/q1ougKglm14uEkPMvQ/05RGmx6G9wvmLTrTI/Q5iPNJLYqNdsDQ7qTGIcNWR+FrHmA==", - "license": "MIT" - }, - "node_modules/mitt": { - "version": "3.0.1", - "resolved": "https://registry.npmjs.org/mitt/-/mitt-3.0.1.tgz", - "integrity": "sha512-vKivATfr97l2/QBCYAkXYDbrIWPM2IIKEl7YPhjCvKlG3kE2gm+uBo6nEXK3M5/Ffh/FLpKExzOQ3JJoJGFKBw==", - "license": "MIT" - }, - "node_modules/mj-context-menu": { - "version": "0.6.1", - "resolved": "https://registry.npmjs.org/mj-context-menu/-/mj-context-menu-0.6.1.tgz", - "integrity": "sha512-7NO5s6n10TIV96d4g2uDpG7ZDpIhMh0QNfGdJw/W47JswFcosz457wqz/b5sAKvl12sxINGFCn80NZHKwxQEXA==", - "license": "Apache-2.0" - }, - "node_modules/nanoid": { - "version": "3.3.11", - "resolved": "https://registry.npmjs.org/nanoid/-/nanoid-3.3.11.tgz", - "integrity": "sha512-N8SpfPUnUp1bK+PMYW8qSWdl9U+wwNWI4QKxOYDy9JAro3WMX7p2OeVRF9v+347pnakNevPmiHhNmZ2HbFA76w==", - "funding": [ - { - "type": "github", - "url": "https://github.com/sponsors/ai" - } - ], - "license": "MIT", - "bin": { - "nanoid": "bin/nanoid.cjs" - }, - "engines": { - "node": "^10 || ^12 || ^13.7 || ^14 || >=15.0.1" - } - }, - "node_modules/node-fetch": { - "version": "2.7.0", - "resolved": "https://registry.npmjs.org/node-fetch/-/node-fetch-2.7.0.tgz", - "integrity": "sha512-c4FRfUm/dbcWZ7U+1Wq0AwCyFL+3nt2bEw05wfxSz+DWpWsitgmSgYmy2dQdWyKC1694ELPqMs/YzUSNozLt8A==", - "license": "MIT", - "dependencies": { - "whatwg-url": "^5.0.0" - }, - "engines": { - "node": "4.x || >=6.0.0" - }, - "peerDependencies": { - "encoding": "^0.1.0" - }, - "peerDependenciesMeta": { - "encoding": { - "optional": true - } - } - }, - "node_modules/npm-run-path": { - "version": "6.0.0", - "resolved": "https://registry.npmjs.org/npm-run-path/-/npm-run-path-6.0.0.tgz", - "integrity": "sha512-9qny7Z9DsQU8Ou39ERsPU4OZQlSTP47ShQzuKZ6PRXpYLtIFgl/DEBYEXKlvcEa+9tHVcK8CF81Y2V72qaZhWA==", - "license": "MIT", - "dependencies": { - "path-key": "^4.0.0", - "unicorn-magic": "^0.3.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/npm-run-path/node_modules/path-key": { - "version": "4.0.0", - "resolved": "https://registry.npmjs.org/path-key/-/path-key-4.0.0.tgz", - "integrity": "sha512-haREypq7xkM7ErfgIyA0z+Bj4AGKlMSdlQE2jvJo6huWD1EdkKYV+G/T4nq0YEF2vgTT8kqMFKo1uHn950r4SQ==", - "license": "MIT", - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/nth-check": { - "version": "2.1.1", - "resolved": "https://registry.npmjs.org/nth-check/-/nth-check-2.1.1.tgz", - "integrity": "sha512-lqjrjmaOoAnWfMmBPL+XNnynZh2+swxiX3WUE0s4yEHI6m+AwrK2UZOimIRl3X/4QctVqS8AiZjFqyOGrMXb/w==", - "license": "BSD-2-Clause", - "dependencies": { - "boolbase": "^1.0.0" - }, - "funding": { - "url": "https://github.com/fb55/nth-check?sponsor=1" - } - }, - "node_modules/oniguruma-to-es": { - "version": "3.1.1", - "resolved": "https://registry.npmjs.org/oniguruma-to-es/-/oniguruma-to-es-3.1.1.tgz", - "integrity": "sha512-bUH8SDvPkH3ho3dvwJwfonjlQ4R80vjyvrU8YpxuROddv55vAEJrTuCuCVUhhsHbtlD9tGGbaNApGQckXhS8iQ==", - "license": "MIT", - "dependencies": { - "emoji-regex-xs": "^1.0.0", - "regex": "^6.0.1", - "regex-recursion": "^6.0.2" - } - }, - "node_modules/open": { - "version": "10.1.2", - "resolved": "https://registry.npmjs.org/open/-/open-10.1.2.tgz", - "integrity": "sha512-cxN6aIDPz6rm8hbebcP7vrQNhvRcveZoJU72Y7vskh4oIm+BZwBECnx5nTmrlres1Qapvx27Qo1Auukpf8PKXw==", - "license": "MIT", - "dependencies": { - "default-browser": "^5.2.1", - "define-lazy-prop": "^3.0.0", - "is-inside-container": "^1.0.0", - "is-wsl": "^3.1.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/open-editor": { - "version": "5.1.0", - "resolved": "https://registry.npmjs.org/open-editor/-/open-editor-5.1.0.tgz", - "integrity": "sha512-KkNqM6FdoegD6WhY2YXmWcovOux45NV+zBped2+G3+V74zkDPkIl4cqh6hte2zNDojtwO2nBOV8U+sgziWfPrg==", - "license": "MIT", - "dependencies": { - "env-editor": "^1.1.0", - "execa": "^9.3.0", - "line-column-path": "^3.0.0", - "open": "^10.1.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/parse-ms": { - "version": "4.0.0", - "resolved": "https://registry.npmjs.org/parse-ms/-/parse-ms-4.0.0.tgz", - "integrity": "sha512-TXfryirbmq34y8QBwgqCVLi+8oA3oWx2eAnSn62ITyEhEYaWRlVZ2DvMM9eZbMs/RfxPu/PK/aBLyGj4IrqMHw==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/parse5": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/parse5/-/parse5-6.0.1.tgz", - "integrity": "sha512-Ofn/CTFzRGTTxwpNEs9PP93gXShHcTq255nzRYSKe8AkVpZY7e1fpmTfOyoIvjP5HG7Z2ZM7VS9PPhQGW2pOpw==", - "license": "MIT" - }, - "node_modules/parse5-htmlparser2-tree-adapter": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/parse5-htmlparser2-tree-adapter/-/parse5-htmlparser2-tree-adapter-6.0.1.tgz", - "integrity": "sha512-qPuWvbLgvDGilKc5BoicRovlT4MtYT6JfJyBOMDsKoiT+GiuP5qyrPCnR9HcPECIJJmZh5jRndyNThnhhb/vlA==", - "license": "MIT", - "dependencies": { - "parse5": "^6.0.1" - } - }, - "node_modules/path-key": { - "version": "3.1.1", - "resolved": "https://registry.npmjs.org/path-key/-/path-key-3.1.1.tgz", - "integrity": "sha512-ojmeN0qd+y0jszEtoY48r0Peq5dwMEkIlCOu6Q5f41lfkswXuKtYrhgoTpLnyIcHm24Uhqx+5Tqm2InSwLhE6Q==", - "license": "MIT", - "engines": { - "node": ">=8" - } - }, - "node_modules/perfect-debounce": { - "version": "1.0.0", - "resolved": "https://registry.npmjs.org/perfect-debounce/-/perfect-debounce-1.0.0.tgz", - "integrity": "sha512-xCy9V055GLEqoFaHoC1SoLIaLmWctgCUaBaWxDZ7/Zx4CTyX7cJQLJOok/orfjZAh9kEYpjJa4d0KcJmCbctZA==", - "license": "MIT" - }, - "node_modules/picocolors": { - "version": "1.1.1", - "resolved": "https://registry.npmjs.org/picocolors/-/picocolors-1.1.1.tgz", - "integrity": "sha512-xceH2snhtb5M9liqDsmEw56le376mTZkEX/jEb/RxNFyegNul7eNslCXP9FDj/Lcu0X8KEyMceP2ntpaHrDEVA==", - "license": "ISC" - }, - "node_modules/postcss": { - "version": "8.5.6", - "resolved": "https://registry.npmjs.org/postcss/-/postcss-8.5.6.tgz", - "integrity": "sha512-3Ybi1tAuwAP9s0r1UQ2J4n5Y0G05bJkpUIO0/bI9MhwmD70S5aTWbXGBwxHrelT+XM1k6dM0pk+SwNkpTRN7Pg==", - "funding": [ - { - "type": "opencollective", - "url": "https://opencollective.com/postcss/" - }, - { - "type": "tidelift", - "url": "https://tidelift.com/funding/github/npm/postcss" - }, - { - "type": "github", - "url": "https://github.com/sponsors/ai" - } - ], - "license": "MIT", - "dependencies": { - "nanoid": "^3.3.11", - "picocolors": "^1.1.1", - "source-map-js": "^1.2.1" - }, - "engines": { - "node": "^10 || ^12 || >=14" - } - }, - "node_modules/preact": { - "version": "10.26.9", - "resolved": "https://registry.npmjs.org/preact/-/preact-10.26.9.tgz", - "integrity": "sha512-SSjF9vcnF27mJK1XyFMNJzFd5u3pQiATFqoaDy03XuN00u4ziveVVEGt5RKJrDR8MHE/wJo9Nnad56RLzS2RMA==", - "license": "MIT", - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/preact" - } - }, - "node_modules/pretty-ms": { - "version": "9.2.0", - "resolved": "https://registry.npmjs.org/pretty-ms/-/pretty-ms-9.2.0.tgz", - "integrity": "sha512-4yf0QO/sllf/1zbZWYnvWw3NxCQwLXKzIj0G849LSufP15BXKM0rbD2Z3wVnkMfjdn/CB0Dpp444gYAACdsplg==", - "license": "MIT", - "dependencies": { - "parse-ms": "^4.0.0" - }, - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/property-information": { - "version": "7.1.0", - "resolved": "https://registry.npmjs.org/property-information/-/property-information-7.1.0.tgz", - "integrity": "sha512-TwEZ+X+yCJmYfL7TPUOcvBZ4QfoT5YenQiJuX//0th53DE6w0xxLEtfK3iyryQFddXuvkIk51EEgrJQ0WJkOmQ==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/regex": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/regex/-/regex-6.0.1.tgz", - "integrity": "sha512-uorlqlzAKjKQZ5P+kTJr3eeJGSVroLKoHmquUj4zHWuR+hEyNqlXsSKlYYF5F4NI6nl7tWCs0apKJ0lmfsXAPA==", - "license": "MIT", - "dependencies": { - "regex-utilities": "^2.3.0" - } - }, - "node_modules/regex-recursion": { - "version": "6.0.2", - "resolved": "https://registry.npmjs.org/regex-recursion/-/regex-recursion-6.0.2.tgz", - "integrity": "sha512-0YCaSCq2VRIebiaUviZNs0cBz1kg5kVS2UKUfNIx8YVs1cN3AV7NTctO5FOKBA+UT2BPJIWZauYHPqJODG50cg==", - "license": "MIT", - "dependencies": { - "regex-utilities": "^2.3.0" - } - }, - "node_modules/regex-utilities": { - "version": "2.3.0", - "resolved": "https://registry.npmjs.org/regex-utilities/-/regex-utilities-2.3.0.tgz", - "integrity": "sha512-8VhliFJAWRaUiVvREIiW2NXXTmHs4vMNnSzuJVhscgmGav3g9VDxLrQndI3dZZVVdp0ZO/5v0xmX516/7M9cng==", - "license": "MIT" - }, - "node_modules/rfdc": { - "version": "1.4.1", - "resolved": "https://registry.npmjs.org/rfdc/-/rfdc-1.4.1.tgz", - "integrity": "sha512-q1b3N5QkRUWUl7iyylaaj3kOpIT0N2i9MqIEQXP73GVsN9cw3fdx8X63cEmWhJGi2PPCF23Ijp7ktmd39rawIA==", - "license": "MIT" - }, - "node_modules/rollup": { - "version": "4.44.2", - "resolved": "https://registry.npmjs.org/rollup/-/rollup-4.44.2.tgz", - "integrity": "sha512-PVoapzTwSEcelaWGth3uR66u7ZRo6qhPHc0f2uRO9fX6XDVNrIiGYS0Pj9+R8yIIYSD/mCx2b16Ws9itljKSPg==", - "license": "MIT", - "dependencies": { - "@types/estree": "1.0.8" - }, - "bin": { - "rollup": "dist/bin/rollup" - }, - "engines": { - "node": ">=18.0.0", - "npm": ">=8.0.0" - }, - "optionalDependencies": { - "@rollup/rollup-android-arm-eabi": "4.44.2", - "@rollup/rollup-android-arm64": "4.44.2", - "@rollup/rollup-darwin-arm64": "4.44.2", - "@rollup/rollup-darwin-x64": "4.44.2", - "@rollup/rollup-freebsd-arm64": "4.44.2", - "@rollup/rollup-freebsd-x64": "4.44.2", - "@rollup/rollup-linux-arm-gnueabihf": "4.44.2", - "@rollup/rollup-linux-arm-musleabihf": "4.44.2", - "@rollup/rollup-linux-arm64-gnu": "4.44.2", - "@rollup/rollup-linux-arm64-musl": "4.44.2", - "@rollup/rollup-linux-loongarch64-gnu": "4.44.2", - "@rollup/rollup-linux-powerpc64le-gnu": "4.44.2", - "@rollup/rollup-linux-riscv64-gnu": "4.44.2", - "@rollup/rollup-linux-riscv64-musl": "4.44.2", - "@rollup/rollup-linux-s390x-gnu": "4.44.2", - "@rollup/rollup-linux-x64-gnu": "4.44.2", - "@rollup/rollup-linux-x64-musl": "4.44.2", - "@rollup/rollup-win32-arm64-msvc": "4.44.2", - "@rollup/rollup-win32-ia32-msvc": "4.44.2", - "@rollup/rollup-win32-x64-msvc": "4.44.2", - "fsevents": "~2.3.2" - } - }, - "node_modules/run-applescript": { - "version": "7.0.0", - "resolved": "https://registry.npmjs.org/run-applescript/-/run-applescript-7.0.0.tgz", - "integrity": "sha512-9by4Ij99JUr/MCFBUkDKLWK3G9HVXmabKz9U5MlIAIuvuzkiOicRYs8XJLxX+xahD+mLiiCYDqF9dKAgtzKP1A==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/search-insights": { - "version": "2.17.3", - "resolved": "https://registry.npmjs.org/search-insights/-/search-insights-2.17.3.tgz", - "integrity": "sha512-RQPdCYTa8A68uM2jwxoY842xDhvx3E5LFL1LxvxCNMev4o5mLuokczhzjAgGwUZBAmOKZknArSxLKmXtIi2AxQ==", - "license": "MIT", - "peer": true - }, - "node_modules/shebang-command": { - "version": "2.0.0", - "resolved": "https://registry.npmjs.org/shebang-command/-/shebang-command-2.0.0.tgz", - "integrity": "sha512-kHxr2zZpYtdmrN1qDjrrX/Z1rR1kG8Dx+gkpK1G4eXmvXswmcE1hTWBWYUzlraYw1/yZp6YuDY77YtvbN0dmDA==", - "license": "MIT", - "dependencies": { - "shebang-regex": "^3.0.0" - }, - "engines": { - "node": ">=8" - } - }, - "node_modules/shebang-regex": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/shebang-regex/-/shebang-regex-3.0.0.tgz", - "integrity": "sha512-7++dFhtcx3353uBaq8DDR4NuxBetBzC7ZQOhmTQInHEd6bSrXdiEyzCvG07Z44UYdLShWUyXt5M/yhz8ekcb1A==", - "license": "MIT", - "engines": { - "node": ">=8" - } - }, - "node_modules/shiki": { - "version": "2.5.0", - "resolved": "https://registry.npmjs.org/shiki/-/shiki-2.5.0.tgz", - "integrity": "sha512-mI//trrsaiCIPsja5CNfsyNOqgAZUb6VpJA+340toL42UpzQlXpwRV9nch69X6gaUxrr9kaOOa6e3y3uAkGFxQ==", - "license": "MIT", - "dependencies": { - "@shikijs/core": "2.5.0", - "@shikijs/engine-javascript": "2.5.0", - "@shikijs/engine-oniguruma": "2.5.0", - "@shikijs/langs": "2.5.0", - "@shikijs/themes": "2.5.0", - "@shikijs/types": "2.5.0", - "@shikijs/vscode-textmate": "^10.0.2", - "@types/hast": "^3.0.4" - } - }, - "node_modules/signal-exit": { - "version": "4.1.0", - "resolved": "https://registry.npmjs.org/signal-exit/-/signal-exit-4.1.0.tgz", - "integrity": "sha512-bzyZ1e88w9O1iNJbKnOlvYTrWPDl46O1bG0D3XInv+9tkPrxrN8jUUTiFlDkkmKWgn1M6CfIA13SuGqOa9Korw==", - "license": "ISC", - "engines": { - "node": ">=14" - }, - "funding": { - "url": "https://github.com/sponsors/isaacs" - } - }, - "node_modules/slick": { - "version": "1.12.2", - "resolved": "https://registry.npmjs.org/slick/-/slick-1.12.2.tgz", - "integrity": "sha512-4qdtOGcBjral6YIBCWJ0ljFSKNLz9KkhbWtuGvUyRowl1kxfuE1x/Z/aJcaiilpb3do9bl5K7/1h9XC5wWpY/A==", - "license": "MIT (http://mootools.net/license.txt)", - "engines": { - "node": "*" - } - }, - "node_modules/source-map-js": { - "version": "1.2.1", - "resolved": "https://registry.npmjs.org/source-map-js/-/source-map-js-1.2.1.tgz", - "integrity": "sha512-UXWMKhLOwVKb728IUtQPXxfYU+usdybtUrK/8uGE8CQMvrhOpwvzDBwj0QhSL7MQc7vIsISBG8VQ8+IDQxpfQA==", - "license": "BSD-3-Clause", - "engines": { - "node": ">=0.10.0" - } - }, - "node_modules/space-separated-tokens": { - "version": "2.0.2", - "resolved": "https://registry.npmjs.org/space-separated-tokens/-/space-separated-tokens-2.0.2.tgz", - "integrity": "sha512-PEGlAwrG8yXGXRjW32fGbg66JAlOAwbObuqVoJpv/mRgoWDQfgH1wDPvtzWyUSNAXBGSk8h755YDbbcEy3SH2Q==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/speakingurl": { - "version": "14.0.1", - "resolved": "https://registry.npmjs.org/speakingurl/-/speakingurl-14.0.1.tgz", - "integrity": "sha512-1POYv7uv2gXoyGFpBCmpDVSNV74IfsWlDW216UPjbWufNf+bSU6GdbDsxdcxtfwb4xlI3yxzOTKClUosxARYrQ==", - "license": "BSD-3-Clause", - "engines": { - "node": ">=0.10.0" - } - }, - "node_modules/speech-rule-engine": { - "version": "4.1.2", - "resolved": "https://registry.npmjs.org/speech-rule-engine/-/speech-rule-engine-4.1.2.tgz", - "integrity": "sha512-S6ji+flMEga+1QU79NDbwZ8Ivf0S/MpupQQiIC0rTpU/ZTKgcajijJJb1OcByBQDjrXCN1/DJtGz4ZJeBMPGJw==", - "license": "Apache-2.0", - "dependencies": { - "@xmldom/xmldom": "0.9.8", - "commander": "13.1.0", - "wicked-good-xpath": "1.3.0" - }, - "bin": { - "sre": "bin/sre" - } - }, - "node_modules/speech-rule-engine/node_modules/commander": { - "version": "13.1.0", - "resolved": "https://registry.npmjs.org/commander/-/commander-13.1.0.tgz", - "integrity": "sha512-/rFeCpNJQbhSZjGVwO9RFV3xPqbnERS8MmIQzCtD/zl6gpJuV/bMLuN92oG3F7d8oDEHHRrujSXNUr8fpjntKw==", - "license": "MIT", - "engines": { - "node": ">=18" - } - }, - "node_modules/stringify-entities": { - "version": "4.0.4", - "resolved": "https://registry.npmjs.org/stringify-entities/-/stringify-entities-4.0.4.tgz", - "integrity": "sha512-IwfBptatlO+QCJUo19AqvrPNqlVMpW9YEL2LIVY+Rpv2qsjCGxaDLNRgeGsQWJhfItebuJhsGSLjaBbNSQ+ieg==", - "license": "MIT", - "dependencies": { - "character-entities-html4": "^2.0.0", - "character-entities-legacy": "^3.0.0" - }, - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/strip-final-newline": { - "version": "4.0.0", - "resolved": "https://registry.npmjs.org/strip-final-newline/-/strip-final-newline-4.0.0.tgz", - "integrity": "sha512-aulFJcD6YK8V1G7iRB5tigAP4TsHBZZrOV8pjV++zdUwmeV8uzbY7yn6h9MswN62adStNZFuCIx4haBnRuMDaw==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/superjson": { - "version": "2.2.2", - "resolved": "https://registry.npmjs.org/superjson/-/superjson-2.2.2.tgz", - "integrity": "sha512-5JRxVqC8I8NuOUjzBbvVJAKNM8qoVuH0O77h4WInc/qC2q5IreqKxYwgkga3PfA22OayK2ikceb/B26dztPl+Q==", - "license": "MIT", - "dependencies": { - "copy-anything": "^3.0.2" - }, - "engines": { - "node": ">=16" - } - }, - "node_modules/tabbable": { - "version": "6.2.0", - "resolved": "https://registry.npmjs.org/tabbable/-/tabbable-6.2.0.tgz", - "integrity": "sha512-Cat63mxsVJlzYvN51JmVXIgNoUokrIaT2zLclCXjRd8boZ0004U4KCs/sToJ75C6sdlByWxpYnb5Boif1VSFew==", - "license": "MIT" - }, - "node_modules/tr46": { - "version": "0.0.3", - "resolved": "https://registry.npmjs.org/tr46/-/tr46-0.0.3.tgz", - "integrity": "sha512-N3WMsuqV66lT30CrXNbEjx4GEwlow3v6rr4mCcv6prnfwhS01rkgyFdjPNBYd9br7LpXV1+Emh01fHnq2Gdgrw==", - "license": "MIT" - }, - "node_modules/trim-lines": { - "version": "3.0.1", - "resolved": "https://registry.npmjs.org/trim-lines/-/trim-lines-3.0.1.tgz", - "integrity": "sha512-kRj8B+YHZCc9kQYdWfJB2/oUl9rA99qbowYYBtr4ui4mZyAQ2JpvVBd/6U2YloATfqBhBTSMhTpgBHtU0Mf3Rg==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - }, - "node_modules/tslib": { - "version": "2.8.1", - "resolved": "https://registry.npmjs.org/tslib/-/tslib-2.8.1.tgz", - "integrity": "sha512-oJFu94HQb+KVduSUQL7wnpmqnfmLsOA/nAh6b6EH0wCEoK0/mPeXU6c3wKDV83MkOuHPRHtSXKKU99IBazS/2w==", - "license": "0BSD" - }, - "node_modules/type-fest": { - "version": "2.19.0", - "resolved": "https://registry.npmjs.org/type-fest/-/type-fest-2.19.0.tgz", - "integrity": "sha512-RAH822pAdBgcNMAfWnCBU3CFZcfZ/i1eZjwFU/dsLKumyuuP3niueg2UAukXYF0E2AAoc82ZSSf9J0WQBinzHA==", - "license": "(MIT OR CC0-1.0)", - "engines": { - "node": ">=12.20" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/uc.micro": { - "version": "1.0.6", - "resolved": "https://registry.npmjs.org/uc.micro/-/uc.micro-1.0.6.tgz", - "integrity": "sha512-8Y75pvTYkLJW2hWQHXxoqRgV7qb9B+9vFEtidML+7koHUFapnVJAZ6cKs+Qjz5Aw3aZWHMC6u0wJE3At+nSGwA==", - "license": "MIT" - }, - "node_modules/unicorn-magic": { - "version": "0.3.0", - "resolved": "https://registry.npmjs.org/unicorn-magic/-/unicorn-magic-0.3.0.tgz", - "integrity": "sha512-+QBBXBCvifc56fsbuxZQ6Sic3wqqc3WWaqxs58gvJrcOuN83HGTCwz3oS5phzU9LthRNE9VrJCFCLUgHeeFnfA==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/unist-util-is": { - "version": "6.0.0", - "resolved": "https://registry.npmjs.org/unist-util-is/-/unist-util-is-6.0.0.tgz", - "integrity": "sha512-2qCTHimwdxLfz+YzdGfkqNlH0tLi9xjTnHddPmJwtIG9MGsdbutfTc4P+haPD7l7Cjxf/WZj+we5qfVPvvxfYw==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/unist-util-position": { - "version": "5.0.0", - "resolved": "https://registry.npmjs.org/unist-util-position/-/unist-util-position-5.0.0.tgz", - "integrity": "sha512-fucsC7HjXvkB5R3kTCO7kUjRdrS0BJt3M/FPxmHMBOm8JQi2BsHAHFsy27E0EolP8rp0NzXsJ+jNPyDWvOJZPA==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/unist-util-stringify-position": { - "version": "4.0.0", - "resolved": "https://registry.npmjs.org/unist-util-stringify-position/-/unist-util-stringify-position-4.0.0.tgz", - "integrity": "sha512-0ASV06AAoKCDkS2+xw5RXJywruurpbC4JZSm7nr7MOt1ojAzvyyaO+UxZf18j8FCF6kmzCZKcAgN/yu2gm2XgQ==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/unist-util-visit": { - "version": "5.0.0", - "resolved": "https://registry.npmjs.org/unist-util-visit/-/unist-util-visit-5.0.0.tgz", - "integrity": "sha512-MR04uvD+07cwl/yhVuVWAtw+3GOR/knlL55Nd/wAdblk27GCVt3lqpTivy/tkJcZoNPzTwS1Y+KMojlLDhoTzg==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0", - "unist-util-is": "^6.0.0", - "unist-util-visit-parents": "^6.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/unist-util-visit-parents": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/unist-util-visit-parents/-/unist-util-visit-parents-6.0.1.tgz", - "integrity": "sha512-L/PqWzfTP9lzzEa6CKs0k2nARxTdZduw3zyh8d2NVBnsyvHjSX4TWse388YrrQKbvI8w20fGjGlhgT96WwKykw==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0", - "unist-util-is": "^6.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/valid-data-url": { - "version": "3.0.1", - "resolved": "https://registry.npmjs.org/valid-data-url/-/valid-data-url-3.0.1.tgz", - "integrity": "sha512-jOWVmzVceKlVVdwjNSenT4PbGghU0SBIizAev8ofZVgivk/TVHXSbNL8LP6M3spZvkR9/QolkyJavGSX5Cs0UA==", - "license": "MIT", - "engines": { - "node": ">=10" - } - }, - "node_modules/vfile": { - "version": "6.0.3", - "resolved": "https://registry.npmjs.org/vfile/-/vfile-6.0.3.tgz", - "integrity": "sha512-KzIbH/9tXat2u30jf+smMwFCsno4wHVdNmzFyL+T/L3UGqqk6JKfVqOFOZEpZSHADH1k40ab6NUIXZq422ov3Q==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0", - "vfile-message": "^4.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/vfile-message": { - "version": "4.0.2", - "resolved": "https://registry.npmjs.org/vfile-message/-/vfile-message-4.0.2.tgz", - "integrity": "sha512-jRDZ1IMLttGj41KcZvlrYAaI3CfqpLpfpf+Mfig13viT6NKvRzWZ+lXz0Y5D60w6uJIBAOGq9mSHf0gktF0duw==", - "license": "MIT", - "dependencies": { - "@types/unist": "^3.0.0", - "unist-util-stringify-position": "^4.0.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/unified" - } - }, - "node_modules/vite": { - "version": "5.4.21", - "resolved": "https://registry.npmjs.org/vite/-/vite-5.4.21.tgz", - "integrity": "sha512-o5a9xKjbtuhY6Bi5S3+HvbRERmouabWbyUcpXXUA1u+GNUKoROi9byOJ8M0nHbHYHkYICiMlqxkg1KkYmm25Sw==", - "license": "MIT", - "peer": true, - "dependencies": { - "esbuild": "^0.21.3", - "postcss": "^8.4.43", - "rollup": "^4.20.0" - }, - "bin": { - "vite": "bin/vite.js" - }, - "engines": { - "node": "^18.0.0 || >=20.0.0" - }, - "funding": { - "url": "https://github.com/vitejs/vite?sponsor=1" - }, - "optionalDependencies": { - "fsevents": "~2.3.3" - }, - "peerDependencies": { - "@types/node": "^18.0.0 || >=20.0.0", - "less": "*", - "lightningcss": "^1.21.0", - "sass": "*", - "sass-embedded": "*", - "stylus": "*", - "sugarss": "*", - "terser": "^5.4.0" - }, - "peerDependenciesMeta": { - "@types/node": { - "optional": true - }, - "less": { - "optional": true - }, - "lightningcss": { - "optional": true - }, - "sass": { - "optional": true - }, - "sass-embedded": { - "optional": true - }, - "stylus": { - "optional": true - }, - "sugarss": { - "optional": true - }, - "terser": { - "optional": true - } - } - }, - "node_modules/vitepress": { - "version": "1.6.3", - "resolved": "https://registry.npmjs.org/vitepress/-/vitepress-1.6.3.tgz", - "integrity": "sha512-fCkfdOk8yRZT8GD9BFqusW3+GggWYZ/rYncOfmgcDtP3ualNHCAg+Robxp2/6xfH1WwPHtGpPwv7mbA3qomtBw==", - "license": "MIT", - "dependencies": { - "@docsearch/css": "3.8.2", - "@docsearch/js": "3.8.2", - "@iconify-json/simple-icons": "^1.2.21", - "@shikijs/core": "^2.1.0", - "@shikijs/transformers": "^2.1.0", - "@shikijs/types": "^2.1.0", - "@types/markdown-it": "^14.1.2", - "@vitejs/plugin-vue": "^5.2.1", - "@vue/devtools-api": "^7.7.0", - "@vue/shared": "^3.5.13", - "@vueuse/core": "^12.4.0", - "@vueuse/integrations": "^12.4.0", - "focus-trap": "^7.6.4", - "mark.js": "8.11.1", - "minisearch": "^7.1.1", - "shiki": "^2.1.0", - "vite": "^5.4.14", - "vue": "^3.5.13" - }, - "bin": { - "vitepress": "bin/vitepress.js" - }, - "peerDependencies": { - "markdown-it-mathjax3": "^4", - "postcss": "^8" - }, - "peerDependenciesMeta": { - "markdown-it-mathjax3": { - "optional": true - }, - "postcss": { - "optional": true - } - } - }, - "node_modules/vue": { - "version": "3.5.17", - "resolved": "https://registry.npmjs.org/vue/-/vue-3.5.17.tgz", - "integrity": "sha512-LbHV3xPN9BeljML+Xctq4lbz2lVHCR6DtbpTf5XIO6gugpXUN49j2QQPcMj086r9+AkJ0FfUT8xjulKKBkkr9g==", - "license": "MIT", - "peer": true, - "dependencies": { - "@vue/compiler-dom": "3.5.17", - "@vue/compiler-sfc": "3.5.17", - "@vue/runtime-dom": "3.5.17", - "@vue/server-renderer": "3.5.17", - "@vue/shared": "3.5.17" - }, - "peerDependencies": { - "typescript": "*" - }, - "peerDependenciesMeta": { - "typescript": { - "optional": true - } - } - }, - "node_modules/vue3-tabs-component": { - "version": "1.3.7", - "resolved": "https://registry.npmjs.org/vue3-tabs-component/-/vue3-tabs-component-1.3.7.tgz", - "integrity": "sha512-nitYlPlTrKCW8msQS1HdtajYNRAfZsSP+2wQQymJDGDCK3um62mXP4oKUgAF5pRe6md86LMRQud7Ic3zmu7Zpg==", - "license": "MIT", - "peerDependencies": { - "vue": "^3.0.0" - } - }, - "node_modules/web-resource-inliner": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/web-resource-inliner/-/web-resource-inliner-6.0.1.tgz", - "integrity": "sha512-kfqDxt5dTB1JhqsCUQVFDj0rmY+4HLwGQIsLPbyrsN9y9WV/1oFDSx3BQ4GfCv9X+jVeQ7rouTqwK53rA/7t8A==", - "license": "MIT", - "dependencies": { - "ansi-colors": "^4.1.1", - "escape-goat": "^3.0.0", - "htmlparser2": "^5.0.0", - "mime": "^2.4.6", - "node-fetch": "^2.6.0", - "valid-data-url": "^3.0.0" - }, - "engines": { - "node": ">=10.0.0" - } - }, - "node_modules/web-resource-inliner/node_modules/domhandler": { - "version": "3.3.0", - "resolved": "https://registry.npmjs.org/domhandler/-/domhandler-3.3.0.tgz", - "integrity": "sha512-J1C5rIANUbuYK+FuFL98650rihynUOEzRLxW+90bKZRWB6A1X1Tf82GxR1qAWLyfNPRvjqfip3Q5tdYlmAa9lA==", - "license": "BSD-2-Clause", - "dependencies": { - "domelementtype": "^2.0.1" - }, - "engines": { - "node": ">= 4" - }, - "funding": { - "url": "https://github.com/fb55/domhandler?sponsor=1" - } - }, - "node_modules/web-resource-inliner/node_modules/entities": { - "version": "2.2.0", - "resolved": "https://registry.npmjs.org/entities/-/entities-2.2.0.tgz", - "integrity": "sha512-p92if5Nz619I0w+akJrLZH0MX0Pb5DX39XOwQTtXSdQQOaYH03S1uIQp4mhOZtAXrxq4ViO67YTiLBo2638o9A==", - "license": "BSD-2-Clause", - "funding": { - "url": "https://github.com/fb55/entities?sponsor=1" - } - }, - "node_modules/web-resource-inliner/node_modules/htmlparser2": { - "version": "5.0.1", - "resolved": "https://registry.npmjs.org/htmlparser2/-/htmlparser2-5.0.1.tgz", - "integrity": "sha512-vKZZra6CSe9qsJzh0BjBGXo8dvzNsq/oGvsjfRdOrrryfeD9UOBEEQdeoqCRmKZchF5h2zOBMQ6YuQ0uRUmdbQ==", - "license": "MIT", - "dependencies": { - "domelementtype": "^2.0.1", - "domhandler": "^3.3.0", - "domutils": "^2.4.2", - "entities": "^2.0.0" - }, - "funding": { - "url": "https://github.com/fb55/htmlparser2?sponsor=1" - } - }, - "node_modules/webidl-conversions": { - "version": "3.0.1", - "resolved": "https://registry.npmjs.org/webidl-conversions/-/webidl-conversions-3.0.1.tgz", - "integrity": "sha512-2JAn3z8AR6rjK8Sm8orRC0h/bcl/DqL7tRPdGZ4I1CjdF+EaMLmYxBHyXuKL849eucPFhvBoxMsflfOb8kxaeQ==", - "license": "BSD-2-Clause" - }, - "node_modules/whatwg-url": { - "version": "5.0.0", - "resolved": "https://registry.npmjs.org/whatwg-url/-/whatwg-url-5.0.0.tgz", - "integrity": "sha512-saE57nupxk6v3HY35+jzBwYa0rKSy0XR8JSxZPwgLr7ys0IBzhGviA1/TUGJLmSVqs8pb9AnvICXEuOHLprYTw==", - "license": "MIT", - "dependencies": { - "tr46": "~0.0.3", - "webidl-conversions": "^3.0.0" - } - }, - "node_modules/which": { - "version": "2.0.2", - "resolved": "https://registry.npmjs.org/which/-/which-2.0.2.tgz", - "integrity": "sha512-BLI3Tl1TW3Pvl70l3yq3Y64i+awpwXqsGBYWkkqMtnbXgrMD+yj7rhW0kuEDxzJaYXGjEW5ogapKNMEKNMjibA==", - "license": "ISC", - "dependencies": { - "isexe": "^2.0.0" - }, - "bin": { - "node-which": "bin/node-which" - }, - "engines": { - "node": ">= 8" - } - }, - "node_modules/wicked-good-xpath": { - "version": "1.3.0", - "resolved": "https://registry.npmjs.org/wicked-good-xpath/-/wicked-good-xpath-1.3.0.tgz", - "integrity": "sha512-Gd9+TUn5nXdwj/hFsPVx5cuHHiF5Bwuc30jZ4+ronF1qHK5O7HD0sgmXWSEgwKquT3ClLoKPVbO6qGwVwLzvAw==", - "license": "MIT" - }, - "node_modules/yoctocolors": { - "version": "2.1.1", - "resolved": "https://registry.npmjs.org/yoctocolors/-/yoctocolors-2.1.1.tgz", - "integrity": "sha512-GQHQqAopRhwU8Kt1DDM8NjibDXHC8eoh1erhGAJPEyveY9qqVeXvVikNKrDz69sHowPMorbPUrH/mx8c50eiBQ==", - "license": "MIT", - "engines": { - "node": ">=18" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/zwitch": { - "version": "2.0.4", - "resolved": "https://registry.npmjs.org/zwitch/-/zwitch-2.0.4.tgz", - "integrity": "sha512-bXE4cR/kVZhKZX/RjPEflHaKVhUVl85noU3v6b8apfQEc1x4A+zBxjZ4lN8LqGd6WZ3dl98pY4o717VFmoPp+A==", - "license": "MIT", - "funding": { - "type": "github", - "url": "https://github.com/sponsors/wooorm" - } - } - } -} diff --git a/docs/package.json b/docs/package.json index 0b836998bcb2..b95faf493e4f 100644 --- a/docs/package.json +++ b/docs/package.json @@ -23,5 +23,8 @@ "open-editor": "^5.0.0", "vitepress": "^1.6.3", "vue3-tabs-component": "^1.3.7" + }, + "devDependencies": { + "prettier": "^3.2.0" } } diff --git a/docs/public/middleware/graph_full.json b/docs/public/middleware/graph_full.json index 8f09680777e2..788e6cff835e 100644 --- a/docs/public/middleware/graph_full.json +++ b/docs/public/middleware/graph_full.json @@ -1 +1 @@ -{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_hardfault_stream", "name": "hardfault_stream", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#41d870", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41a8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84184", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d842", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_status", "name": "internal_combustion_engine_status", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#88d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#5bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d897", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#72d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8bf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#417bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#8ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#44d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41a3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#bbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#41bfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#419dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8ac41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#b041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#99d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d89d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8b3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance_fused", "name": "obstacle_distance_fused", "type": "topic", "color": "#41d0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#4170d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#4164d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841a6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d8415d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84151", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#aad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d84179", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#b5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d848", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41b9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d84190", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d85d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41b3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_esc_serial_passthru", "name": "esc_serial_passthru", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d892", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#7d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#b541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d88c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#4197d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#8e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#bb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d84195", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#41d87b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d8d0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4148d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#5b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#7241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#b0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#4181d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#6c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#aa41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d841ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d84173", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8b741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#6cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#66d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#61d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d853", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d89b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8a641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#7dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d864", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d881", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#4142d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_battery_info", "name": "battery_info", "type": "topic", "color": "#d89041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#9941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#c141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8ce41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d8a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#4192d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#6641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#a441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d8419b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d87341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#c1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#6141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#8841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#418cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#a4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84146", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#4153d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d87341", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8415d", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84157", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d87f41", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d841ce", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_info", "color": "#d89041", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_info", "color": "#d89041", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d87341", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#9941d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8a641", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d89b41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8a641", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#a4d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#9fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#99d841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d85f", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d864", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#4197d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#417bd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841ac", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84162", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8ac41", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_info", "color": "#d89041", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8bd41", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#bbd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#b5d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#b0d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#aad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#8241d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d841ce", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841a6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d84173", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84146", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d886", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#b541d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841b2", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d88c", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88441", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#77d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#a441d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#93d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#8ed841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#88d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#82d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#7dd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d886", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d897", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d89d", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8ae", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#41aed8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41a8d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#9341d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d8417f", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#7dd841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#9341d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#61d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#5bd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#50d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#4ad841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d848", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d84e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d8d0", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d853", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4441d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#6141d8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#5bd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#55d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#41d5d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#6141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d841d4", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#d841c8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a1", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84151", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#41d870", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_status", "color": "#41d875", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#41d87b", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d881", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d84190", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d892", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#41d5d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance_fused", "color": "#41d0d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#d841ce", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8b241", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#b0d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d841a6", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#d84173", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8a8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d241d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d886", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8b3", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8b9", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84162", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d8a141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8b741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8c341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8c841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8ce41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d8d441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_esc_serial_passthru", "color": "#c6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#a4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#72d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#5bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#55d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#44d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d842", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d853", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d881", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d892", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8bf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_obstacle_distance", "color": "#41d5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41cad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#41bfd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41b9d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41b3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#4181d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#6141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#b541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#bb41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d841ce", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841c3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841a6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84179", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84151", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#9f41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#b541d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c3", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841b2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8417f", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84c41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8b741", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#ccd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#6cd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#66d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d864", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8c4", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8ca", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d8d5", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#419dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#414ed8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4148d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#bb41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841a6", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d84190", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84168", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84162", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d859", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#4153d8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#4192d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#418cd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d85d41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#4186d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#4142d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8b9", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#41a3d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#4170d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#416ad8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#4164d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#415fd8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#4159d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#4170d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#416ad8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#4164d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#415fd8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#4159d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#4175d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#4170d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#416ad8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#4164d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#415fd8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#4159d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41a3d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c3", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8415d", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d84157", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#418cd8", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#4153d8", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#4153d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#4142d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#bb41d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d88a41", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#6141d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87941", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#5541d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#8241d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#8e41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d8419b", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d84195", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d853", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#4441d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#6141d8", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#7241d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#d7d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#41d881", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#4153d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d841d4", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#d841c8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a1", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84179", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84151", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87941", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4a41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#6641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#6c41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#d841d4", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d841c8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a1", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84184", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#9941d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#5b41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d8b741", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#7d41d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_battery_info", "color": "#d89041", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41c4d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#4142d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#cc41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41d853", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#41d8a3", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#c141d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8415d", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84157", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c3", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#8841d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841bd", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#7741d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#b0d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#5041d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#6141d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#8241d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d2d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#d84641", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#d85141", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d85741", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#d86241", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#c1d841", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#7dd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#9341d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#b041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c3", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841b7", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d8415d", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84157", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414c", "style": "dashed"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87941", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#bbd841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#b0d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#77d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d89d", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d8415d", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d84179", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84151", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d84162", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d84162", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d87341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84162", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d87341", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d841ce", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#4192d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d841bd", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8a641", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#5bd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841a6", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#4192d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d8418a", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84641", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d87f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89541", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d7d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d2d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#c1d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#bbd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#b5d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#b0d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#aad841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#a4d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#6cd841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d864", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#41d87b", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8a8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8b3", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8b9", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8ca", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d8d5", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41cad8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#4197d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#418cd8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4148d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#4142d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#5b41d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#6141d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#6641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#7741d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#8241d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#8e41d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#9941d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414c", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84146", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#99d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#7dd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8b9", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#4153d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#9341d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#b041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d8415d", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84157", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#d86e41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#6141d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8b741", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d84162", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87941", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d87f41", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d88a41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d2d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d892", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d89d", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#5541d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#8241d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d8419b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84151", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#c1d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#d841b7", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#9f41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84162", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84162", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d87f41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88441", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#82d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84162", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d87f41", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#8ed841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#88d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#7dd841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d897", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d84162", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84146", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d87f41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8b3", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#419dd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d84162", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84146", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d87f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89541", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8ac41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84162", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d89541", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#5bd841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#55d841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#44d841", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d842", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8b3", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#419dd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84168", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d853", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#5b41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#6641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84162", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#6641d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#6c41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d84195", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#61d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#50d841", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d841bd", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_hardfault_stream", "color": "#aa41d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4a41d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d87941", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d89541", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#c1d841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41d864", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d84162", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d84162", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84162", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d84162", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#d85141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#4153d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84641", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d87f41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d89d", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#419dd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#8241d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#9f41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d8415d", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d8418a", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#ccd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84162", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#d2d841", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#d841ce", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#d841bd", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#418cd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d84641", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#d2d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d892", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d84179", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84151", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8b3", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d741d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84162", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84162", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8b9", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d85d41", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87941", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88441", "style": "normal"}, {"source": "t_battery_info", "target": "m_mavlink", "color": "#d89041", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89541", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d89b41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d8a141", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8a641", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d8b241", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8bd41", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8c341", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8ce41", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d8d441", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d7d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d2d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#c1d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#bbd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#b5d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#b0d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#a4d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#9fd841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#6cd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#5bd841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#4ad841", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d848", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d84e", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d853", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d85f", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d864", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d86a", "style": "normal"}, {"source": "t_internal_combustion_engine_status", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d892", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8b3", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8b9", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8ca", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d8d0", "style": "normal"}, {"source": "t_obstacle_distance_fused", "target": "m_mavlink", "color": "#41d0d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41a3d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#419dd8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#417bd8", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#4153d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4148d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4441d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#5b41d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#6141d8", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#7241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#8241d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#a441d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#bb41d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d241d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841b7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d8419b", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d84173", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d8415d", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84146", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84c41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84157", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841b2", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d8418a", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89541", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8ac41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84162", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#9fd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#6641d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#d8418a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d87f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d89541", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d864", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d86a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d84162", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8bd41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#66d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d864", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d892", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8c4", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41a8d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41a3d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#414ed8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84162", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84146", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d84641", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#6141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8b3", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d84162", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d87341", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84162", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d86a", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8b9", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#4181d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d8a3", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d8a3", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d8a3", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d8a3", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#41d8a3", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#d86241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d8b3", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#41cad8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#41a3d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#419dd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#4175d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#4170d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#416ad8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#4164d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#415fd8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#4159d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d8418a", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d85141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d8b3", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#41cad8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#419dd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#4175d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#4170d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#416ad8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#4164d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#415fd8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#4159d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d8418a", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d85141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d8b3", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#41cad8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#419dd8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#4175d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#4170d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#416ad8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#4164d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#415fd8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#4159d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d8418a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#419dd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d841a6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d8418a", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84641", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#6141d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#bb41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d84162", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89541", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8b241", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#9fd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84184", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841c8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841a1", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d87341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d7d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#b5d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#5b41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#6641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#7741d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#7d41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d8419b", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d84195", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d853", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d85d41", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d85d41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d88c", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#41d8a3", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41d8b3", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#c141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#d841bd", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#6641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841bd", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#5541d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d8bd41", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41d86a", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#c141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#61d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d853", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d859", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d864", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d88c", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d8a3", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8b3", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#41bfd8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41b9d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41b3d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#c141d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84162", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d8416e", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d8418a", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#8841d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841b7", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d88c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#d84641", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#d85141", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#d86e41", "style": "normal"}, {"source": "t_esc_serial_passthru", "target": "m_voxl_esc", "color": "#c6d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#77d841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#61d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d859", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#41d870", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d88c", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#41d8a3", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41d8b3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d84162", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#77d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d84162", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d87f41", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#72d841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d864", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#419dd8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#a441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841ac", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84162", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#d8ad41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#417dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#c541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_status", "name": "internal_combustion_engine_status", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#ba41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d86341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#76d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d85241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#81d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#65d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#af41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#bad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d84163", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d84152", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#cbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41bcd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8c7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#5341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#7041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#cb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance_fused", "name": "obstacle_distance_fused", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#92d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#70d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41c7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#4161d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d84146", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#5fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#53d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#414ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41b0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41abd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d84a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#41d861", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_serial_passthru", "name": "esc_serial_passthru", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/MavlinkTunnel.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#4e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#7641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d8414c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#48d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#42d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#6541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#8741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#a341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d89041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d841b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d8415d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#d85d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#afd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d84641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#d8b241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d8ab", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4144d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#8141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841ad", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#d84179", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#c5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41d8bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#5f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#87d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d87d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d8b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#4178d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#4841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#4ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41d844", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41cdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d84c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#a3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41d878", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#d841b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d8b841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#9241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d84190", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d8cd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#4241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_voxl2_io", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#4841d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d8415d", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#5f41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#4161d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#4841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#cbd841", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41d8bc", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d89c41", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#9dd841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#5f41d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#4841d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41d844", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#d84190", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#a9d841", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance_fused", "color": "#d841cf", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#41d883", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41d8bc", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#9dd841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d89c41", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#9dd841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#afd841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d86841", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#9241d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d8be41", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#9241d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d8b0", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#4172d8", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d84190", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#d89641", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#d89c41", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#a9d841", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#a9d841", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#48d841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d8b841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#8141d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d841b2", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d89f", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d8ab", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#65d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d86341", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d8c1", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#98d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84185", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#9841d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#d8417f", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d84c41", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#afd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#42d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4144d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#a341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87941", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#4166d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#d841b8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d88a41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d894", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d87f41", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#6541d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d841c9", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#4241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d85241", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41c1d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d8a5", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#c041d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d8cf41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#87d841", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#7bd841", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84185", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#9841d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8c7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41c7d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#70d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d86841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#a941d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#5fd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41d855", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d6d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#afd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#8cd841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d8b6", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#c5d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#7041d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#5341d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#4e41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#41d86c", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#59d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#4194d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#c541d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d866", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#c0d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#41d8b0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#a9d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84146", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#4194d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d866", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#c541d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87941", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#c0d841", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#9dd841", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#d8be41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d86341", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#d87441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#59d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#4194d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#c541d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d866", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#41d883", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#c0d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d84157", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#9dd841", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d84196", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#41a5d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#4183d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#41d87d", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d841a1", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#414ad8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#8741d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d841be", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d84163", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#41d850", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d8419c", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d8414c", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#5941d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#d8ad41", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_status", "color": "#41d88e", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#7041d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#5341d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#4e41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#41d86c", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#b4d841", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d1d841", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d84163", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#8c41d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41b0d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d84168", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#70d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d86841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d6d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#8cd841", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d8c941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d84641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#81d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#8141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#70d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#6ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#d85d41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d86341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#41b6d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d86e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#b441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41abd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#419ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#d88541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#59d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#418ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#53d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#4178d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d89c41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#48d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d8a741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#d841d4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d85b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#41d861", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#d8c341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_esc_serial_passthru", "color": "#415bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41d878", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d8d441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_obstacle_distance", "color": "#41d883", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d8419c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#4241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#b4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d8b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d84163", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d84157", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#92d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84146", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#ba41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#d84141", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#bad841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#d84174", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#41cdd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#4189d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#41d8b6", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#76d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#417dd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#4ed841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#cb41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#41d850", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#c5d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#8141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d85741", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d87f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d89041", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d8a141", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#48d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#d8b241", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d841c9", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d872", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d841a7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d6d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#414ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#d84179", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d84152", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d8c941", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84185", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#7641d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d8b6", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41bcd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d84163", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#9841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#c5d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84185", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d84163", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#af41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#9841d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#419fd8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#6a41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#7041d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#5341d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#4e41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#41d86c", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#41d889", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#af41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#4ed841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d8419c", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d8414c", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d841c9", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d841c3", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841ad", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#4ed841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#416cd8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8c7", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#a3d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#41d89a", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d84a", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d8cd", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d3d8", "style": "dashed"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d894", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#4183d8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#70d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#41b0d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41abd8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#419fd8", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#d88541", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#53d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#4ed841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d89c41", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#d8ad41", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d87d", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#414ad8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d894", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#d8417f", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#41d89a", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d8ab", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#a3d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d89c41", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#70d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d8d3", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d3d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d6d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#70d841", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#4172d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d841c9", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#4183d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d8ab", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d87d", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41d844", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d894", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#d8a741", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#d84190", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#41d3d8", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#41d883", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#d8c341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d841c9", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d8a141", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d841ad", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d8ab", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d894", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d841ad", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#9241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#9d41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#4183d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d89c41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#41d87d", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#4183d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#4183d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#9241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#9dd841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d841c9", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#41b0d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#41d8a5", "style": "normal"}, {"source": "t_esc_serial_passthru", "target": "m_voxl_esc", "color": "#415bd8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#4ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#41d87d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#d8ad41", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#a3d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#4166d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d894", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d894", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d87f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#9d41d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d87441", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d6d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#9d41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d841c9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d841c9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d841c9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d841c9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#4166d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d841c9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d841c9", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#48d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#414ad8", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d841ad", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#9d41d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#a3d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#a3d841", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#a3d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#a3d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#a3d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#a3d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#d841c3", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#41d89a", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#41d87d", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#a3d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d894", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d8b841", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41d8d3", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d841c9", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#70d841", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#41d8d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#41d878", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#4144d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84157", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d3d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#81d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841ad", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#4150d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d86341", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d6d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d841ad", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#41d861", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#5fd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d88a41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d84c41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d8a5", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#afd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41d878", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#9241d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#42d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d8a741", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#b441d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d841c9", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d88a41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41d878", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#ba41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#4189d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#414ad8", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#70d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#8741d8", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#417dd8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#41d855", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#c5d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841ad", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41d878", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d8d441", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d841c9", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#bad841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#70d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d8c941", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#6541d8", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#87d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d3d8", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#7641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#7b41d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41c7d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d85741", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#70d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#8741d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d86841", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#a341d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d87441", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#a941d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#b441d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#419fd8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#5fd841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d88a41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d89041", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#418ed8", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#4183d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d84a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d8a741", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#d8b241", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#42d841", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d841c9", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d841c3", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d8c341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841ad", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d872", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41d878", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d8d441", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#414ad8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d84190", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#4241d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#4841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#afd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8c7", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d8cd", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d841c9", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d85b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841ad", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#9d41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d841c9", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d841c9", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#9241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#4166d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#92d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8c7", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d8d3", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#d85d41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#59d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d8c341", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d84c41", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#b4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841ad", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#8741d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#afd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#cb41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#a341d8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#414ad8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87941", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4144d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#8741d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#92d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#419fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#41d3d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#7041d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#6a41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#418ed8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#5341d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#41d8a5", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#d8416e", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#70d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d841c9", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d841a1", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#41a5d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#c541d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#c541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#41d3d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d841ad", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#41d8ab", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#41d87d", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#65d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#419fd8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#d8417f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d841c3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d8ab", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#4183d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#4ed841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#d8ad41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#41d87d", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#41b0d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84185", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d8a5", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#4183d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#afd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#70d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#8741d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#42d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d6d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d3d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#d841b8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#70d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#cb41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d86841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#414ad8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#a941d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87941", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#70d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d8414c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#92d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#d841c3", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#419fd8", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#a9d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#419fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#d841c3", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#7041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#41d3d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#6a41d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#5341d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#41d8a5", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#4e41d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#d8416e", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#70d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d3d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d8b0", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d86341", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d3d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#5f41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d6d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#70d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#70d841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d8c941", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d8a5", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d8b6", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41bcd8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d8cf41", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#9841d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8c7", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#a9d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#c5d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#59d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#d8c341", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#b4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#4183d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d84146", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#414ad8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4144d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d841c3", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d84641", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d85241", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d84c41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d86341", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d86841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d87441", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d86e41", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87941", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d89041", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#d8b241", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#d8c341", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d8d441", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d6d841", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#cbd841", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#c0d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#b4d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#afd841", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#9dd841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#92d841", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#8cd841", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#7bd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#70d841", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#65d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#5fd841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#48d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#42d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d84a", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_internal_combustion_engine_status", "target": "m_mavlink", "color": "#41d88e", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d8a5", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41d8bc", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d8c1", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8c7", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d8cd", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d8d3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d3d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41cdd8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41c1d8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#4183d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#4178d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#4161d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#414ad8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#4241d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#5f41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#8741d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#8c41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#af41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#c541d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d141d8", "style": "normal"}, {"source": "t_obstacle_distance_fused", "target": "m_mavlink", "color": "#d841cf", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d841c3", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d841b2", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#d841b8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841ad", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d84163", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d8415d", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d84157", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d84152", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#70d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d6d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#d84152", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d841c9", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#d84179", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d87f41", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#d84174", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#b4d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#70d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#8c41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#48d841", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d6d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d141d8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#414ad8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#af41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#9841d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#8741d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#70d841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d87f41", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#419ad8", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#41d850", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d841c9", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#d841b8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841ad", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#4155d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#414ad8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d84152", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d6d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#d84152", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#afd841", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#42d841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#41d878", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#419fd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#41d3d8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#6a41d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#7041d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#418ed8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#41d8a5", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#41d86c", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#70d841", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#5341d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#41d889", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#d8419c", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#d84152", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#af41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d841c9", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d8a5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841ad", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#414ad8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8c7", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d841c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d841c3", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#416cd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841ad", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#c041d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#9d41d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d8cd", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d3d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#59d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#70d841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d84146", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4144d8", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_full_no_mavlink.json b/docs/public/middleware/graph_full_no_mavlink.json index 0aa5bd90a632..eaf719b975d5 100644 --- a/docs/public/middleware/graph_full_no_mavlink.json +++ b/docs/public/middleware/graph_full_no_mavlink.json @@ -1 +1 @@ -{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#ced841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#41d863", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84191", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#52d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#c741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41c2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#ce41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#6fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d896", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#419ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#4196d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84165", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d8415e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#aad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d84183", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#b8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d86541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#aa41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841cc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d89141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4163d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8cc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#6f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#d86d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8c541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8af41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#76d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8416d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#b841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d89e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#414dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#5241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d88341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#c7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#7641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d84d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d88341", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84165", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415e", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d89141", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#c041d8", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d88341", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#8c41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8af41", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8af41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#a2d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#9bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#94d841", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d854", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41bbd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841c5", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8416d", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d87441", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8b641", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8cc41", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#c0d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#b8d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#b1d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#aad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#6f41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#c041d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841bd", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84199", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84148", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d879", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#aa41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841cc", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d880", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8417b", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d89941", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#6fd841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#9b41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#8cd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#85d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#7ed841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#76d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d88f", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d896", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8ac", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41d1d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#8541d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d8418a", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#76d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#8541d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8417b", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#59d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#52d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#43d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d845", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4a41d8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#52d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#4ad841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#41d8d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#4a41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#c741d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d841b6", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d84191", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84157", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#41d863", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d871", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d841a0", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d887", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#41d8d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#c041d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8bd41", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#b1d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d841bd", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84199", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8a5", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d879", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8b4", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8bb", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8416d", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8417b", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d89941", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#9441d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#aa41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841cc", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8418a", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84f41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8417b", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8c541", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#ced841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#68d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#60d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d854", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8c2", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8ca", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d8d1", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41c2d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#416ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4163d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#b141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841bd", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d841a0", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84174", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8416d", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d84d", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#4171d8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#41b4d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#41acd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d86541", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41a5d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#415bd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8bb", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#419ed8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#4196d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#418fd8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#4187d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#419ed8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#4196d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#418fd8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#4187d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#419ed8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#4196d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#418fd8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#4187d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84165", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415e", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#41acd8", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#4171d8", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#4171d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#415bd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#b141d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d8a041", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4a41d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d88a41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4145d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#6f41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#7e41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841af", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d841a7", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d845", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#4a41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#d8d341", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#41d871", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#4171d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#c741d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d841b6", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d84191", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84183", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84157", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d88a41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4154d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#5941d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#c741d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841b6", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84191", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#8c41d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#4341d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d8c541", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#6841d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#415bd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41d845", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#41d89e", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#b841d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84165", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415e", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#7641d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d641d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#6041d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#b1d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#414dd8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#4a41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#6f41d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#d6d841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#41d85b", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#d84841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#d85741", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d85e41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#d86d41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#d87b41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#c7d841", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#d8a741", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#76d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#8541d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#a241d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84165", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415e", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414f", "style": "dashed"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d8416d", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d88a41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#c0d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#b1d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#6fd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d896", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#9b41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84165", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d84183", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84157", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d8416d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d8416d", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d88341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8416d", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d88341", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#c041d8", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d641d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8af41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#52d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841bd", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d89141", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d8a741", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8bd41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d8d341", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#d6d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#c7d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#c0d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#b8d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#b1d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#aad841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#a2d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#68d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d854", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#41d86a", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8a5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8b4", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8bb", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8ca", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d8d1", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41bbd8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#41acd8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4163d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#415bd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4154d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#414dd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#6f41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#7e41d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8416d", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414f", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84148", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#94d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#76d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8bb", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#4171d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#8541d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#a241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84165", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d8415e", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d8416d", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#d87b41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#4a41d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d8416d", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d88a41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d89141", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d8a041", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#d6d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d887", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d896", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#6f41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84157", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#c7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#d841d3", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8416d", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d8416d", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d89141", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d89941", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8416d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8416d", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d89141", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#8cd841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#85d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#76d841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d88f", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8ac", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d8416d", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84148", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d89141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#41c2d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d8416d", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84148", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d89141", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d8a741", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8b641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8416d", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d8a741", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#52d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#4ad841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41c2d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84174", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d845", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4154d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#5241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8416d", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#5941d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d841a7", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#59d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#43d841", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d641d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4154d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d88a41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d8a741", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#c7d841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d8416d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d8416d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8416d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d8416d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d8416d", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d8416d", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d85e41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d89141", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d896", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41c2d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#6f41d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#9441d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84165", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84199", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#ced841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8416d", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#d6d841", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#c041d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#41acd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d84841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#d6d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d887", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d84183", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84157", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d8a741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8416d", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8416d", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8416d", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d89941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8416d", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84f41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8415e", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841cc", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84199", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d8a741", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8b641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8416d", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#9bd841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#5941d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#d84199", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d89141", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d8a741", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d854", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d8416d", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8cc41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#60d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d854", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d887", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8c2", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d1d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41cad8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#416ad8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#b141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8416d", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84148", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#41d89e", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d84841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8b4", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8416d", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d88341", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8416d", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d85b", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8bb", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d89e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d89e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d89e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d89e", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#41d89e", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#d86d41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#41cad8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#41c2d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#419ed8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#4196d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#418fd8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#4187d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#4179d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#41c2d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#419ed8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#4196d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#418fd8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#4187d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#4179d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#41c2d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#419ed8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#4196d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#418fd8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#4187d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#4179d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d84199", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41c2d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84199", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#4a41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#b141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d8416d", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d8a741", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8bd41", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84191", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841b6", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d88341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d8d341", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#b8d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4154d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#6041d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#6841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d841a7", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d845", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d85e41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d86541", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#d8a741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d8416d", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d85e41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d86541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#41d880", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#41d89e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41d8b4", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#b841d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#d641d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4154d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#414dd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d641d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#4145d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d8cc41", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41d85b", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#b841d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#59d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d845", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d84d", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d854", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d880", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d89e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8b4", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#b841d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8416d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d8417b", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84199", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#7641d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841d3", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#d87b41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#41d880", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#d641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#d84841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#d85741", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#d87441", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#d87b41", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#59d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#41d84d", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#41d863", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#41d880", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#41d89e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d8416d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d8416d", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d89141", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d854", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41c2d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#9b41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8416d", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_lightware_sf45_serial", "name": "lightware_sf45_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_io_bypass_control", "name": "io_bypass_control", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_template_module", "name": "template_module", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_linux_pwm_out", "name": "linux_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_rpm_simulator", "name": "rpm_simulator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_ets_airspeed", "name": "ets_airspeed", "type": "Module", "color": "#666666"}, {"id": "m_sagetech_mxs", "name": "sagetech_mxs", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_rpm_capture", "name": "rpm_capture", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1_mag", "name": "lsm9ds1_mag", "type": "Module", "color": "#666666"}, {"id": "m_pps_capture", "name": "pps_capture", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls_pwm", "name": "ll40ls_pwm", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_leddar_one", "name": "leddar_one", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_bmi088_i2c", "name": "bmi088_i2c", "type": "Module", "color": "#666666"}, {"id": "m_iam20680hp", "name": "iam20680hp", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_iridiumsbd", "name": "iridiumsbd", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_uavcannode", "name": "uavcannode", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_microbench", "name": "microbench", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16477", "name": "adis16477", "type": "Module", "color": "#666666"}, {"id": "m_adis16497", "name": "adis16497", "type": "Module", "color": "#666666"}, {"id": "m_icm40609d", "name": "icm40609d", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_rpi_rc_in", "name": "rpi_rc_in", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_vertiq_io", "name": "vertiq_io", "type": "Module", "color": "#666666"}, {"id": "m_tattu_can", "name": "tattu_can", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_uwb_sr150", "name": "uwb_sr150", "type": "Module", "color": "#666666"}, {"id": "m_tcbp001ta", "name": "tcbp001ta", "type": "Module", "color": "#666666"}, {"id": "m_mpl3115a2", "name": "mpl3115a2", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_voxl2_io", "name": "voxl2_io", "type": "Module", "color": "#666666"}, {"id": "m_mappydot", "name": "mappydot", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_icm42605", "name": "icm42605", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_iim42653", "name": "iim42653", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_roboclaw", "name": "roboclaw", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_voxl_esc", "name": "voxl_esc", "type": "Module", "color": "#666666"}, {"id": "m_neopixel", "name": "neopixel", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_afbrs50", "name": "afbrs50", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_gy_us42", "name": "gy_us42", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_lsm9ds1", "name": "lsm9ds1", "type": "Module", "color": "#666666"}, {"id": "m_mpu6500", "name": "mpu6500", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_asp5033", "name": "asp5033", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pcf8583", "name": "pcf8583", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_tap_esc", "name": "tap_esc", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_mb12xx", "name": "mb12xx", "type": "Module", "color": "#666666"}, {"id": "m_pga460", "name": "pga460", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_bmi270", "name": "bmi270", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_bmi085", "name": "bmi085", "type": "Module", "color": "#666666"}, {"id": "m_sch16t", "name": "sch16t", "type": "Module", "color": "#666666"}, {"id": "m_cyphal", "name": "cyphal", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_bmm350", "name": "bmm350", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_ms4515", "name": "ms4515", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina220", "name": "ina220", "type": "Module", "color": "#666666"}, {"id": "m_voxlpm", "name": "voxlpm", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_lps25h", "name": "lps25h", "type": "Module", "color": "#666666"}, {"id": "m_ms5837", "name": "ms5837", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_srf02", "name": "srf02", "type": "Module", "color": "#666666"}, {"id": "m_srf05", "name": "srf05", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_auav", "name": "auav", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#7641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d86541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_internal_combustion_engine_control", "name": "internal_combustion_engine_control", "type": "topic", "color": "#76d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d89141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d841c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d8416d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#419ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41d88f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#4196d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84191", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#d84f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#aad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#418fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#ce41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#d841af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84183", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d863", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#c7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d8c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d8415e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d8414f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#41d84d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#aa41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d89e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d84148", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41c2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_iridiumsbd_status", "name": "iridiumsbd_status", "type": "topic", "color": "#414dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_obstacle_distance", "name": "obstacle_distance", "type": "topic", "color": "#d841cc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ObstacleDistance.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#a2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#5941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d84841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#d8c541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#6fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#59d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d887", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d84165", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d88341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d89941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#52d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d896", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d85e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#5241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8cc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#ced841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8af41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#4163d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pps_capture", "name": "pps_capture", "type": "topic", "color": "#b841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d84157", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_uwb", "name": "sensor_uwb", "type": "topic", "color": "#d86d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#b8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#c741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#6f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d84199", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#d85741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#4187d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#a241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_voxl2_io", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_voxl2_io", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#5241d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d89941", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#5241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#68d841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d887", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d89941", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#5241d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#ced841", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_linux_pwm_out", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_rpm", "color": "#d841bd", "style": "dashed"}, {"source": "m_rpm_capture", "target": "t_pwm_input", "color": "#8c41d8", "style": "dashed"}, {"source": "m_ll40ls_pwm", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_mb12xx", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_vehicle_attitude", "color": "#6841d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_lightware_sf45_serial", "target": "t_obstacle_distance", "color": "#d841cc", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_pga460", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_leddar_one", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_afbrs50", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_gy_us42", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_srf02", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_srf05", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_mappydot", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_adis16477", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_adis16497", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_lsm9ds1", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_bmi088_i2c", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_bmi270", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_bmi085", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm40609d", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_mpu6500", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm42605", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_iim42653", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_iam20680hp", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_sch16t", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#68d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d887", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#d841a7", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#68d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#5941d8", "style": "dashed"}, {"source": "m_cyphal", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_cyphal", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_lsm9ds1_mag", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_bmm350", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#85d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d6d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#85d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_ms4515", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_auav", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_auav", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_asp5033", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_ets_airspeed", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d8a5", "style": "dashed"}, {"source": "m_pps_capture", "target": "t_pps_capture", "color": "#b841d8", "style": "dashed"}, {"source": "m_rpi_rc_in", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#8c41d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_voxl_esc", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_vertiq_io", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_iridiumsbd", "target": "t_iridiumsbd_status", "color": "#414dd8", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_uavcannode", "target": "t_gps_inject_data", "color": "#41d887", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_ina220", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_voxlpm", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_tattu_can", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_pcf8583", "target": "t_rpm", "color": "#d841bd", "style": "dashed"}, {"source": "m_rpm_simulator", "target": "t_rpm", "color": "#d841bd", "style": "dashed"}, {"source": "m_sagetech_mxs", "target": "t_transponder_report", "color": "#d84148", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_tap_esc", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_uwb_sr150", "target": "t_sensor_uwb", "color": "#d86d41", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_tcbp001ta", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_mpl3115a2", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_lps25h", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_ms5837", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d84165", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_io_bypass_control", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d841c5", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#d8c541", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#60d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#d85741", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d84199", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d89e", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d84841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41cad8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d841a7", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#7ed841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#4163d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#aad841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#d87b41", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d8b641", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d845", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d8bd41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d88341", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41bbd8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d8415e", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#94d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d87441", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41d85b", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d85e41", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#c0d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#a241d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d863", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d880", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d841a7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#5941d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#8cd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#6841d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d8c2", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#52d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41c2d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d845", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#418fd8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#d841af", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#41d84d", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#9bd841", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#d841bd", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d8d341", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#41d871", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#4179d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84183", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#4145d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#41d8a5", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#6f41d8", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d84199", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#4145d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#41d871", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#a2d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#4179d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#68d841", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#d6d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#68d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#aa41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#41b4d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#c741d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#d8af41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_obstacle_distance", "color": "#d841cc", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d841c5", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#41d871", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#41d86a", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#4179d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#4171d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d84191", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#4145d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84183", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#d84157", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#4180d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#4154d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d88a41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d8414f", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#41d8ac", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#c7d841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#41acd8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d89141", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d8417b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41d8bb", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#7e41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#415bd8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#4196d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d845", "style": "dashed"}, {"source": "m_internal_combustion_engine_control", "target": "t_internal_combustion_engine_control", "color": "#76d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#418fd8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#d841af", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#41d84d", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8ca", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#415bd8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#41a5d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d845", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d8418a", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#41d1d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#41d880", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#5941d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d854", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#41d8b4", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d89141", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#d84f41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#b1d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d86541", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d8416d", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#52d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#4ad841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#416ad8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#41c2d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#419ed8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d8d1", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#8541d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#59d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d87441", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#c041d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d88341", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8a041", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#4187d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d880", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#c7d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d896", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#7641d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#b8d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d84165", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d84148", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d854", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#52d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#b141d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41c2d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#43d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#415bd8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d641d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41d88f", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#415bd8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#d841d3", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#d84141", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#ce41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#418fd8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#d841af", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#4a41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#41d84d", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#6041d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#41d88f", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#b1d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d8417b", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#7e41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#c0d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#6fd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d88341", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#b1d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#4341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d841a0", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#9b41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8cc41", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8a741", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#6841d8", "style": "dashed"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl2_io", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl2_io", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl2_io", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl2_io", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl2_io", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl2_io", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl2_io", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl2_io", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl2_io", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl2_io", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl2_io", "color": "#d8b641", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#6fd841", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_capture", "color": "#b841d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_uavcan", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#6fd841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#d85741", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d88341", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d8b641", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#d8c541", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d8cc41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d841b6", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d879", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d887", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#c7d841", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d841a0", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#b1d841", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#4a41d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d887", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d841b6", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#41d880", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#9bd841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#41acd8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d87441", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d841b6", "style": "normal"}, {"source": "t_pps_capture", "target": "m_camera_trigger", "color": "#b841d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d88341", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_px4io", "color": "#76d841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d8b641", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#ced841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_linux_pwm_out", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_linux_pwm_out", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_linux_pwm_out", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_linux_pwm_out", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_linux_pwm_out", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_linux_pwm_out", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_linux_pwm_out", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_linux_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_linux_pwm_out", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_linux_pwm_out", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_linux_pwm_out", "color": "#d8b641", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#9441d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_ll40ls_pwm", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_lightware_sf45_serial", "color": "#6841d8", "style": "normal"}, {"source": "t_obstacle_distance", "target": "m_lightware_sf45_serial", "color": "#d841cc", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_lightware_sf45_serial", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d88341", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#7641d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_dshot", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d8b641", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8cc41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#6841d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#9bd841", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#85d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#4154d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d887", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cyphal", "color": "#4154d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_cyphal", "color": "#68d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_cyphal", "color": "#41d8ac", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_roboclaw", "color": "#4154d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#85d841", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pca9685_pwm_out", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pca9685_pwm_out", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#d8b641", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_pps_capture", "color": "#68d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxl_esc", "color": "#d88341", "style": "normal"}, {"source": "t_led_control", "target": "m_voxl_esc", "color": "#d841a0", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_voxl_esc", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_voxl_esc", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_voxl_esc", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_voxl_esc", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_voxl_esc", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_voxl_esc", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_voxl_esc", "color": "#d85741", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxl_esc", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_voxl_esc", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_voxl_esc", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_voxl_esc", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_voxl_esc", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_voxl_esc", "color": "#d8b641", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_vertiq_io", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vertiq_io", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_vertiq_io", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_vertiq_io", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_vertiq_io", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_vertiq_io", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_vertiq_io", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_vertiq_io", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_vertiq_io", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_vertiq_io", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_vertiq_io", "color": "#d8b641", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d84199", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#41d86a", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#9bd841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#41d880", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#9bd841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d88341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d88341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina220", "color": "#d88341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina220", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_voxlpm", "color": "#d88341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_voxlpm", "color": "#aad841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d88341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_sagetech_mxs", "color": "#d88341", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_sagetech_mxs", "color": "#68d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_sagetech_mxs", "color": "#d84148", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_sagetech_mxs", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d88341", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#6fd841", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#9bd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d841a0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d841a0", "style": "normal"}, {"source": "t_led_control", "target": "m_neopixel", "color": "#d841a0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#d841a0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d841a0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d841a0", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_tap_esc", "color": "#76d841", "style": "normal"}, {"source": "t_led_control", "target": "m_tap_esc", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_tap_esc", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_tap_esc", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_tap_esc", "color": "#4154d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tap_esc", "color": "#d8cc41", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_tap_esc", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_tap_esc", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_tap_esc", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_tap_esc", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_tap_esc", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_tap_esc", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_tap_esc", "color": "#d8b641", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d8b641", "style": "normal"}, {"source": "t_sensor_uwb", "target": "m_uwb_sr150", "color": "#d86d41", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#6f41d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#41a5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d88341", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_io_bypass_control", "color": "#d88a41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_microbench", "color": "#d8af41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_microbench", "color": "#d841b6", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_microbench", "color": "#a2d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_microbench", "color": "#41bbd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#9b41d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_template_module", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d841c5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#8541d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84191", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8a041", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d88341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d89e", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#41b4d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d8415e", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#9441d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d841a7", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8af41", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#aa41d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#85d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d8c2", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d88341", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#9441d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8af41", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d841b6", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#52d841", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d86541", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8416d", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d8415e", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#4ad841", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#a241d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#6841d8", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#419ed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#6fd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#c741d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#9441d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d84157", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8af41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#41acd8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#6841d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#6fd841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d8d1", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#8c41d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#68d841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d85e41", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#59d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#9441d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#9b41d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#a241d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d87441", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#b141d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d88341", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#c741d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8a741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#41acd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8af41", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d841b6", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d86a", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d863", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d880", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d841a7", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d6d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#c7d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#4154d8", "style": "normal"}, {"source": "t_iridiumsbd_status", "target": "m_commander", "color": "#414dd8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d896", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d89e", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#4341d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#5241d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d84157", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#9bd841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#5941d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#6841d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d8c2", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#6fd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d879", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d88341", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#41d86a", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d88341", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#85d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#c0d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d88341", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d84199", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#c7d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8ca", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#6fd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#d84f41", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84183", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d84841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#4171d8", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#4180d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41cad8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#41acd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d88341", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d879", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d845", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#41acd8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#d84141", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#d8417b", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d841b6", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#418fd8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#4a41d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#41d84d", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#6fd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#6fd841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#9bd841", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d8414f", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d8414f", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d88a41", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_gz_bridge", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#d85741", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#60d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_internal_combustion_engine_control", "target": "m_pwm_out_sim", "color": "#76d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#6fd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#d8c541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#4154d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d8418a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#b1d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#d85741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d879", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4a41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#41d8ac", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#9b41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d88341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#8541d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d89e", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#d84f41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84174", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d8415e", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d880", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d841a7", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#41acd8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d88341", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d84199", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#d84f41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84174", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#aad841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#5941d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#8cd841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#6841d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#4163d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#c7d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d8415e", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d88341", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#41d1d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d879", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#9bd841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d88341", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_internal_combustion_engine_control", "color": "#d88341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_internal_combustion_engine_control", "color": "#41d879", "style": "normal"}, {"source": "t_rpm", "target": "m_internal_combustion_engine_control", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_internal_combustion_engine_control", "color": "#4a41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#d84141", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#d8417b", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#ce41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d841b6", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#418fd8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d8415e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#4a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d879", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#41d84d", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d841b6", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d8a5", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d841c5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d880", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d89941", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d8415e", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d84165", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#6841d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d88341", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d8bd41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#c0d841", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84174", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#52d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d8415e", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d641d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41c2d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#43d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#c7d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d8ca", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84183", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d8d341", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#4171d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d88341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d88341", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#8541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#41d880", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#a241d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#6fd841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8ca", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#41a5d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#b8d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d841b6", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#4187d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d880", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#a241d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#416ad8", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d87441", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d84148", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41d88f", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d88341", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#4196d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#6fd841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#8541d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d89141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#41acd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#4163d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#c7d841", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d8415e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#6841d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#8541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d8415e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#415bd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#d8af41", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#a2d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d89e", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#8541d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#d84141", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d841b6", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#ce41d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#6041d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d8415e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#4a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d879", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#41d84d", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#418fd8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#6841d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#41d88f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#c7d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#6fd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d8415e", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#415bd8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#c0d841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#4341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d88341", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#6fd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#41bbd8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8a741", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#9bd841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d84841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84183", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d8d341", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#6841d8", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v2.json b/docs/public/middleware/graph_px4_fmu-v2.json index 63b785f3cc74..9799ca4f8450 100644 --- a/docs/public/middleware/graph_px4_fmu-v2.json +++ b/docs/public/middleware/graph_px4_fmu-v2.json @@ -1 +1 @@ -{"nodes": [{"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41c9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d8419f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d86041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41d8c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84160", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d89f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d8414b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_battery_status", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d87f41", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#6a41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84b41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#7fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#75d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#6ad841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d855", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d860", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d88a", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41c9d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#41a9d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#9f41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841be", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84160", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86a41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8a941", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8be41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#a9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#9fd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#94d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#8ad841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#5541d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#be41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841b4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d84175", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d8414b", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d875", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841c9", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d84b", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#417fd8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4155d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#4141d8", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#414bd8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d84194", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d894", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#a941d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#4175d8", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#4141d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d875", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d89f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8a9", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84160", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d88a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d89f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8b441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8c941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#c9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#bed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#b4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#4bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d84b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d87f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d8b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41b4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4175d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#416ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#4141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#4b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#9441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#9f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#b441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#be41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#c941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#7541d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#8a41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#c941d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841c9", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d8417f", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d8416a", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#4175d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#414bd8", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#416ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8b441", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#60d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#55d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d860", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8be", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41d8c9", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d3d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#419fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4194d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#9441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d84194", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84160", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84b41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d86041", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84b41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d86041", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d86a", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d88a", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#41bed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#418ad8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#9f41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d341d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d841d3", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8a9", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d88a41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#bed841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4160d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#5541d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#6041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a9", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d8419f", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d84b", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#417fd8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#4155d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#9f41d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#9f41d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84160", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d87f41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84b41", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84b41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85541", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89441", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#bed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#b4d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#a9d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#9fd841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#8ad841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#7fd841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#60d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d89f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8be", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41d8c9", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41d8d3", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41c9d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#418ad8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4175d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#416ad8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4155d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#4141d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#5541d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#6041d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#6a41d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d8419f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84160", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d8414b", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#6ad841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84160", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8b441", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d88a41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#b4d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d87f", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4160d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#5541d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84160", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84160", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d84b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84b41", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d3d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#5541d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#7541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d8419f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84160", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d89f", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#b441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84160", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d89f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8a9", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84160", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84b41", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d86041", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d88a41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89441", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d89f41", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8be41", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#c9d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#bed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#b4d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#9fd841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#7fd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#4bd841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d86a", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d89f", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8a9", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d8b4", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41d3d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#41a9d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#417fd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#416ad8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#4141d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#5541d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d8419f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84160", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d8414b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84160", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d8418a", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89441", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8a941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84160", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8be41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#55d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d860", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d87f", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8b4", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#419fd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d8418a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84160", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d8414b", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84b41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d86a41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d87541", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d875", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d341d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84b41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d86a41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d87541", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d875", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d89f", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d84160", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d86a", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8a9", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41b4d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d88a", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d87f41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#bed841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#9fd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4175d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#4141d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#4b41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841be", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d8419f", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d84b", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#9f41d8", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_mpu6000", "name": "mpu6000", "type": "Module", "color": "#666666"}, {"id": "m_lsm303d", "name": "lsm303d", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_l3gd20", "name": "l3gd20", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#b441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d89f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#8a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#9f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d84b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#41d8a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41d3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d841d3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#8ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41d8c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41c9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8419f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#9fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d84160", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#60d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d86041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#6041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d88a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8414b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#b4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#41a9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d8418a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_board_adc", "target": "t_adc_report", "color": "#41a9d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d86041", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d8b4", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d8418a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d3d841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#d84160", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d84160", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d3d841", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d8418a", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_mpu6000", "target": "t_sensor_gyro", "color": "#d8b441", "style": "dashed"}, {"source": "m_l3gd20", "target": "t_sensor_gyro", "color": "#d8b441", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_mag", "color": "#41d87f", "style": "dashed"}, {"source": "m_lsm303d", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#41d87f", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41d8c9", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d8c941", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d8417f", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#417fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#417fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#4175d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#bed841", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41d8c9", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d88a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#9f41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d8c941", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d855", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d8417f", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#8ad841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#417fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d88a41", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#416ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#60d841", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#9f41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#41d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d89f", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d84155", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d87541", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#419fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8417f", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#41d86a", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#8ad841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41d8c9", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d841a9", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#a9d841", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#55d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#8a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#94d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#9f41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d84b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#41b4d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d89f41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d841d3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#418ad8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d88a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d841b4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#41d894", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#6041d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#6ad841", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#75d841", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#9f41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#a941d8", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#5541d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#7541d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#41d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#c941d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d86a41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#6041d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#8ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41d3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d87541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#9441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#8ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d87f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#9f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#b441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#be41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#41bed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d855", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d89f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d841d3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#418ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#4194d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d875", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d8a941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8b441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#41d87f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#4160d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8419f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d84194", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d8418a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d8416a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#4141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#41d8a9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d8b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41d8be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#4b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8414b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d87f41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d8a941", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#6ad841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d85541", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#9fd841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d87f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#c9d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#b4d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d84b41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#8ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#75d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41c9d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#9f41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#4bd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#41d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d860", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#418ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d875", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d841be", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#416ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#4141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#4b41d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d86a41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d8416a", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d8be41", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d88a", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41d8be", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d89441", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#4155d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d841c9", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#7fd841", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#41a9d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#417fd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d3d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d3d841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d88a41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41d8c9", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#8ad841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d841a9", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d8417f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#6041d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#417fd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#417fd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41d8c9", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#bed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#7541d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#41d841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d8417f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#6041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#8ad841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#7fd841", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#41a9d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#41d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#c9d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#7541d8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41d8c9", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d84b41", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#8a41d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d86041", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d86a41", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d87541", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#9441d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#75d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#9f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#41d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d89441", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d84b", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#c941d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d860", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d89f41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#418ad8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#419fd8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#417fd8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d841c9", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#4175d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#416ad8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#41d87f", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d841b4", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d88a", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#41d894", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d84194", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d8418a", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d8416a", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d8b4", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#41d8a9", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#41d841", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d89f", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d341d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d86a41", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#4b41d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#4194d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#75d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8d3", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d8be41", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#7f41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d88a", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41d8be", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#4155d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#41d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#9fd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d89f41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#8ad841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d84175", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d841be", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#41d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#9fd841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d89f41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#418ad8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d841c9", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#417fd8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#7541d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#8ad841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#7541d8", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#c941d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d86a41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d85541", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d86a41", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d89f41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d341", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#c9d841", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#75d841", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#60d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d860", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#41d86a", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#41d88a", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d8b4", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41d8be", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8d3", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41c9d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#418ad8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#4194d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#417fd8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#416ad8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#414bd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#4141d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#7541d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#8a41d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#9f41d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#b441d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d841d3", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d841b4", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8419f", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d8418a", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d84160", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d84155", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8414b", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d8a941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d89f41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d841d3", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#75d841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d89f41", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d87f41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#75d841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#a9d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d341d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#b4d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8d3", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#416ad8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#4141d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#4bd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#8ad841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#41d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#55d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#418ad8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#94d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d89f41", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41d3d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d86a41", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d855", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d8416a", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8b441", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#41d87f", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d88a", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#8a41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#4155d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d341d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#41a9d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d841c9", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v4.json b/docs/public/middleware/graph_px4_fmu-v4.json index ff7ab8543fb0..0ba5a09f7ad1 100644 --- a/docs/public/middleware/graph_px4_fmu-v4.json +++ b/docs/public/middleware/graph_px4_fmu-v4.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#c741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#c0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#4197d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d85d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#79d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84188", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#45d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d8a4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#5fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#4170d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d856", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d849", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d850", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#4191d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#b3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#72d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d843", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#41b1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841d6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8af41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41b8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#ad41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#65d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d8ab", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#a0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#b341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84195", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#cdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#add841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d863", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41abd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41a4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#86d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d89e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#5f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#9941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d897", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#4184d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#6c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#a041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d841a2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4163d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#4541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#7241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#a6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41c5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#4177d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#6541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#cd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8bc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#c7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#58d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#52d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d870", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4143d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#c041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841d0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#6cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4156d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d8a241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d877", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d87d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#415dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_battery_info", "name": "battery_info", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d891", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#419ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4150d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#7941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#a641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d8b1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#4149d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#5241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#8641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#ba41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#bad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#5841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#417dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d884", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#99d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d87541", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d88241", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#cd41d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_info", "color": "#d88f41", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_info", "color": "#d88f41", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d87541", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#7941d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8a941", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d89c41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8a941", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#99d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#93d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#8cd841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d877", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d87d", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d8b1", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#4184d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#4170d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841bc", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8af41", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8c341", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#bad841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#b3d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#add841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#a6d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#a0d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#6541d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#cd41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84195", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84147", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#4b41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d891", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#9941d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841c3", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d897", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#65d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#8641d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#86d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#7fd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#79d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#72d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#6cd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d891", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d8a4", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d8ab", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8be", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#419ed8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#4197d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#7241d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84188", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#6cd841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#7241d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4bd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#45d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d849", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d850", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d863", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d86a", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41cbd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d870", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4156d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4b41d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#bad841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d88a", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d8419c", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d89e", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d8b1", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8b641", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#a6d841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84195", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#d8417b", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b8", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#ba41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d891", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8c5", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8cb", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d8a241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8bc41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8c941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d4d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#cdd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#99d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#5fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#45d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d843", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d856", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d85d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d870", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d884", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d88a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d89e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8d2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41bed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#41b1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41abd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41a4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#4177d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#5f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#8c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#9941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#a041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#ad41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#c041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#cd41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841d6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84195", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84182", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84154", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#7f41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#9941d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d6", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841c3", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84188", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84e41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#cdd841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#cdd841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8bc41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#c0d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#58d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#52d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d87d", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d2d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41c5d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#418ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#416ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4163d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#a041d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d8419c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8416e", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#5f41d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#5f41d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#5f41d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#417dd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d86141", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#5f41d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d884", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8cb", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#4191d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d6", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d8b1", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#415dd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#cdd841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d8b1", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4b41d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#5841d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#cdd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4143d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#6541d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#6c41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a9", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d841a2", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d870", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#4156d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#4b41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4150d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#5241d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#c741d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d441d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841af", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8418f", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d8b1", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#4541d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#5f41d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_battery_info", "color": "#d88f41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#bad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d8b1", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41b8d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#415dd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#a641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#b341d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d6", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841d0", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#a6d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#4149d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#4b41d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#6541d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#c7d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#6cd841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#7241d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#9341d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d6", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841c9", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87b41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#b3d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#a6d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#65d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d8ab", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#8641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84161", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84154", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d87541", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84168", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d87541", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d841d0", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8a941", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#45d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84195", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84741", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89541", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8b641", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#cdd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#c7d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#bad841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#b3d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#add841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#a6d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#a0d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#99d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#58d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d87d", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8c5", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8cb", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d2d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41c5d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41bed8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#4184d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#417dd8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4163d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#415dd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#4149d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#4541d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4b41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#5841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#6541d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#6c41d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#7941d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d841a2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84168", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#8cd841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#6cd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8cb", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#7241d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#9341d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d8415b", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8bc41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4bd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d891", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d897", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d841d0", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d88241", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#c7d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d89e", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d8ab", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4143d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#6541d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84154", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#bad841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84168", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84168", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d88241", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88841", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#72d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d88241", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#7fd841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#79d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#6cd841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8a4", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8be", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d88241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8c5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#418ad8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#9941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89541", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8af41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#45d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d843", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d856", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d85d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8c5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#418ad8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8416e", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d870", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#4541d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#5241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4150d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d87b41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d89541", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#bad841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41d87d", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#65d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d88241", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d8ab", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#418ad8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#6541d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#7f41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#9941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d841a2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84161", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d88a", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84195", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#c0d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d84741", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#c7d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d89e", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4143d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84154", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8c5", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#c041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#5841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84168", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88841", "style": "normal"}, {"source": "t_battery_info", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89541", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d8a241", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d8b641", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8c341", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d041", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d641", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d4d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#cdd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#c7d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#bad841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#b3d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#add841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#a6d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#99d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#86d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#58d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#45d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d843", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41d849", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d850", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d863", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d86a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d870", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d877", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d87d", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d884", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d89e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8c5", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d2d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41cbd8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41b8d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#419ed8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#4191d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#418ad8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#4170d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4163d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4156d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#4149d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#4541d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4b41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#5841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#6541d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#8641d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#a041d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#b341d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#ba41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#c741d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d441d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d841a2", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84188", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8415b", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#9941d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84195", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89541", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8af41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8c341", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#52d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d87d", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d89e", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#4197d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#4191d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#416ad8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#a041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4bd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41d891", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d897", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d841d0", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4bd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d891", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d897", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d841d0", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4bd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d891", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d897", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d841d0", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d87541", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84168", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d884", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8cb", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#4177d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d8b1", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d8b1", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d8b1", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d8b1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#418ad8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#9941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84195", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84741", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89541", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8b641", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#93d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841af", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d441d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841af", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d87541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#cdd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#add841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#4541d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#5841d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#5f41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#6541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d841a2", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d870", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d86141", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4150d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#4149d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#5241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#5841d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841d0", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#a641d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4bd841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d870", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d87d", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d891", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d897", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d8b1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8c5", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#41b1d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41abd8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41a4d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#a641d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#ad41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84168", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841d6", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#9941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841c9", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d88241", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#5fd841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d87d", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8d2", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#418ad8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#8641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#cd41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84195", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84188", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84168", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250_i2c", "name": "mpu9250_i2c", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm20608g", "name": "icm20608g", "type": "Module", "color": "#666666"}, {"id": "m_vectornav", "name": "vectornav", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_mpu9250", "name": "mpu9250", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#a5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#41d873", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#a541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#4173d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#84d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d88d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#9ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#418dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#8441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#9e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#d8c441", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d8c441", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41a1d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#41d893", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d84196", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d84196", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d88f41", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d88f41", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d88f41", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d8a341", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#9841d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#4145d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#abd841", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#41a7d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#4159d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#41c8d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#41a7d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41c8d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#4159d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_icm20608g", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_mpu9250", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_mpu9250_i2c", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_selection", "color": "#71d841", "style": "dashed"}, {"source": "m_vectornav", "target": "t_estimator_status", "color": "#d341d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_gps", "color": "#41c8d8", "style": "dashed"}, {"source": "m_vectornav", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#d8418f", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#50d841", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#50d841", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#50d841", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#50d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#50d841", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#9841d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#4145d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#abd841", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41d893", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#7ed841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#9841d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4145d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#abd841", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#4152d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#6ad841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#41d893", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d8a341", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d8a341", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41d89a", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#ab41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#9841d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#6ad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#4145d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#abd841", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#5641d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#7141d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41d893", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#c641d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#d89c41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84141", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841c4", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#9141d8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#8bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d841b0", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#b9d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d86141", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d86e41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#abd841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4145d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#4186d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#91d841", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#4341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#49d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#7141d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#41bbd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#41d866", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#9e41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d3d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#ccd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#414bd8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#71d841", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41d893", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#8b41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d88d", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d8419c", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#7741d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#d84189", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#9ed841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d8b641", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d88d", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#43d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#d8bd41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#415fd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d8415b", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#5d41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#41d8ce", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#d841a3", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84182", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#5d41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d841a3", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#56d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d84e41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4179d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#6a41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d5d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d8c1", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#63d841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#d88941", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#bf41d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#41d866", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#414bd8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#41bbd8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d341d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8a1", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#5041d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8417b", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d88d", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#b241d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#50d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d84147", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41ced8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d85441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#41d84b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#d85b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#7141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41c8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d86841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#d88941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d86141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d88f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#7e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#41d859", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#419ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#41d866", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#418dd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#4180d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#41d880", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d841b6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41d893", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#4173d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#b2d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#4159d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#4152d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8418f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#4941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#98d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d8416e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d84168", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d84154", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#d8414e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#5dd841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#7741d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#41d886", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d84b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84182", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#8b41d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d87541", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#cc41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84141", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84741", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d86841", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d87b41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41b4d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#41d859", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d8a941", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#41d866", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#41d873", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d841d1", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#d8d141", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d841a9", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#b9d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d84161", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#63d841", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8417b", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#84d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41d86c", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d8c8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d84b", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4193d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#77d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#41d8bb", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#b941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#71d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d88f41", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#5dd841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#9841d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d88241", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4145d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#abd841", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#41d845", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41c8d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#8441d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d841ca", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d8b041", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d8a7", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#41c1d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#a5d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#5dd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d89641", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41d8ae", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#84d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d8c8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d84b", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d85f", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d8c8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#84d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#41d84b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#5d41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d841a3", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d8d5", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41aed8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#416cd8", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#4166d8", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#41c8d8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#414bd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84141", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#41d873", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d85f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d88d", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#416cd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#4186d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#abd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d8ca41", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#4159d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#4159d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41c1d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d841bd", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d841bd", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d841bd", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#41d85f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41d88d", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#416cd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#4186d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#abd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84141", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d84189", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d85f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d88d", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#416cd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#4186d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#abd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d85f", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#7141d8", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d8c441", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#abd841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84141", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#414bd8", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d8a341", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#41d893", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#b9d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#5dd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d85f", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#419ad8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#4186d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d8ca41", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d841bd", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d88d", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4179d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#4173d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#416cd8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#b9d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#4166d8", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#b2d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#4159d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#414bd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#41d8c8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#ccd841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#414bd8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#5dd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#63d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d84189", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d341d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#9ed841", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d841b6", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84141", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d84189", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d8c441", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#7141d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#4941d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#49d841", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41ced8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41c8d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#41d845", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#7141d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41c1d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d87b41", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d88f41", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#6ad841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#8441d8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d8a341", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8b041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d85f", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#9e41d8", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#b941d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#bf41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841d7", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#d8d141", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41d893", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d3d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#ccd841", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8a1", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d8a7", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d841a9", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#b9d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#8bd841", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d8416e", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#5641d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#7ed841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d84161", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#77d841", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d8d5", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#71d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#41d8c8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#84d841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#5d41d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d841a3", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41aed8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8b4", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d85f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#5641d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d8a7", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d85441", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#41d8bb", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#77d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#71d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#63d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#5dd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84141", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d8a341", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d84189", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d85f", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41d893", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d85f", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#41d886", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841c4", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#5641d8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841c4", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8b641", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#9e41d8", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#a541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#5641d8", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d879", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#7141d8", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8415b", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d84141", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#41d85f", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#6341d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#41d866", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#63d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841c4", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#91d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41d893", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#4941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84741", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#41d866", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#7141d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d852", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#63d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41c1d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8b041", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84141", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#41d8c8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#41d886", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#41d866", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#5641d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#b941d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#71d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#414bd8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#abd841", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#41d85f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d841b6", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d8a7", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#63d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84141", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d85f", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41d893", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8417b", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#b241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d86e41", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d86841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#d8d141", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d741", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#a5d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#9ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#71d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#63d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#5dd841", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#56d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#49d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#41d859", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d85f", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41d89a", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41d893", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d8a7", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#41d8bb", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#41d8c8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41d8ce", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41c8d8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#41bbd8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#41a7d8", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#418dd8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#4159d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#4152d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#414bd8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#4341d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#4941d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#5641d8", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#8441d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#9841d8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841d7", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d841b0", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84182", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d84154", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#84d841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d87541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841c4", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841c4", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#91d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84141", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#41d859", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d85f", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#41d866", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#9e41d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41d86c", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#bfd841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#b9d841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#414bd8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#63d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#4341d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#4180d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8417b", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#4152d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d841c4", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#414bd8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#50d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#49d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841c4", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8b041", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41c1d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#41d8bb", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41d8ae", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#b941d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#71d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d88f41", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d8c441", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d85f", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d88d", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4179d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#416cd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4145d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#4186d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#abd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d8ca41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#a5d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#a5d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#a5d841", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#9841d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d88241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d85f", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8b041", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#41d845", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41c1d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d85f", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#b241d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841c4", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84182", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#9ed841", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#63d841", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v5.json b/docs/public/middleware/graph_px4_fmu-v5.json index 0ac93836b9d5..7173a0525ba8 100644 --- a/docs/public/middleware/graph_px4_fmu-v5.json +++ b/docs/public/middleware/graph_px4_fmu-v5.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#c941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#c3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8b8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#419fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8418d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d858", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#7cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84187", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d89f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#4172d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#83d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#4198d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#b6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#76d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#41b8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#4192d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841d4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8ae41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41bfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#9641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#b041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#69d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8bf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8c5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d8415a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#a3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#b641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#b0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d85e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41c5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41b2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d8419a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#41abd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841ba", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d898", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#9c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841c7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d892", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#418bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#7041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#a341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d865", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4165d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#7641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8c141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#4178d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#6941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8ba41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8ce41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#c9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#5cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#4fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d86b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#c341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d89a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#96d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#70d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4158d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#8341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84167", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d86d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d872", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d878", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d885", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#415ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_battery_info", "name": "battery_info", "type": "topic", "color": "#d88d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d88b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#417ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#7c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8c741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d8ab", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#4f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#bc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8416d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#bcd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#416bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#5c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#4185d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d87e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8b441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#9cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d87441", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d88141", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d041d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_info", "color": "#d88d41", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_info", "color": "#d88d41", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d87441", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#7c41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8a741", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d89a41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8a741", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#9cd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#96d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#90d841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d872", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d878", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#418bd8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#4172d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841ba", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84167", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86741", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8ae41", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8c141", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d85a41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#bcd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#b6d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#b0d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#a9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#a3d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#6941d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d041d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841b4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84194", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417a", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84147", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d88b", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#9c41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841c1", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d892", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88741", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#69d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#8941d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#89d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#83d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#7cd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#76d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#70d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d88b", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d89f", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d8a5", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8b8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#41a5d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#419fd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#7641d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84187", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#70d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#7641d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#4fd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#49d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d845", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d84b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d85e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d865", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d2d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d86b", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4158d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#4941d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#bcd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d885", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d8419a", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d898", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8b441", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b2", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#bc41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d88b", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8bf", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8c5", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84167", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d8a141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8ba41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8c741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8ce41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d0d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#9cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#63d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#49d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d858", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d86b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d885", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d898", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8cb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d8d2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41c5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#41b8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41b2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#41abd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#4178d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#4941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#9041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#9c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#a341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#b041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#c341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841d4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841b4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84194", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84181", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84154", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88741", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#8341d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#9c41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d4", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841c1", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84187", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84d41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84174", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#d0d841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#d0d841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8ba41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#c3d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#5cd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#56d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d878", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8d2", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41cbd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#4192d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#416bd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4165d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#a341d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d8419a", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8416d", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84167", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#d85a41", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#4185d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d85a41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d85a41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d86141", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d85a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#417ed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#415ed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8c5", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#4198d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d4", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415a", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#415ed8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d87e", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#d0d841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#4941d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#5c41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87a41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d0d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4145d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#6941d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#7041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a7", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d841a1", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#5641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87a41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#4152d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#4f41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#c941d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841ae", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8418d", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#414bd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#4341d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d85a41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d86d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_battery_info", "color": "#d88d41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#bcd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d8ab", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41bfd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#415ed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#a941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#b641d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415a", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d4", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841ce", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#c9d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#70d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#7641d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#9641d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d4", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841c7", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415a", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414d", "style": "dashed"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87a41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#b6d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#a9d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#69d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d8a5", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84161", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4145d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d84181", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84154", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d84167", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d87441", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#69d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84167", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d87441", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d841ce", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8a741", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#49d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84194", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84741", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d88141", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89441", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8b441", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d0d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#c9d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#bcd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#b6d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#b0d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#a9d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#a3d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#9cd841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#5cd841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d878", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b2", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8bf", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8c5", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d8d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41c5d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#418bd8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#4185d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4165d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#415ed8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#4f41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#5c41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#6941d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#7041d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#7c41d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#9041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841c7", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84167", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414d", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#90d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#70d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8c5", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#7641d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#9641d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d8415a", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d84167", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8ba41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d86741", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d86d41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#4fd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d88b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d892", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d84167", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87a41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d88141", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#c9d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d898", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d8a5", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#6941d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#7041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84154", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#bcd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#69d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84167", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#8341d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84167", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84167", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d88141", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88741", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#76d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84167", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84167", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d88141", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#83d841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#7cd841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#70d841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d89f", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8b8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d84167", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d88141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8bf", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#4192d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d84167", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d88141", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89441", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8ae41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84174", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84167", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d89441", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#49d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d852", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d858", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8bf", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#4192d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8416d", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d86b", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#4f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84167", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4152d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d87a41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d89441", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#bcd841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41d878", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#69d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84167", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d88141", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d8a5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#4192d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#6941d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#8341d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84161", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d885", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84194", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#c3d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84167", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8bf", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#c341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84167", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84167", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8c5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84167", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d85a41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87a41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d88141", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88741", "style": "normal"}, {"source": "t_battery_info", "target": "m_mavlink", "color": "#d88d41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89441", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d89a41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d8a141", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8a741", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d8b441", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8c141", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8c741", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8ce41", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d441", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d6d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d0d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#c9d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#bcd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#b6d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#b0d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#9cd841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#96d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#5cd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#49d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d85e", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d865", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d86b", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d872", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d878", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d87e", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d898", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8bf", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8c5", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d8d2", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d2d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41bfd8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41a5d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#4198d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#4192d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#4172d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4165d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4158d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#5c41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#6941d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#a341d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#b641d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#bc41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#c941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841c7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8418d", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84187", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417a", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84174", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88741", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84167", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84d41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8415a", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841c1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84194", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89441", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8ae41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84174", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84167", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d88141", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d89441", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d878", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d87e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d84167", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8c141", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#56d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d878", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d898", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8d2", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#419fd8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#4198d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#416bd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#a341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84167", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d86741", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#d86d41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#4fd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#41d88b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#41d892", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#d841ce", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d86741", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d86d41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#4fd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d88b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d892", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d841ce", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d86741", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d86d41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#4fd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d88b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d892", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d841ce", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d86741", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d86d41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#4fd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d88b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d892", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8bf", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#417ed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d84167", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d87441", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89441", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84167", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d87e", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8c5", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#4178d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d8ab", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d8ab", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d8ab", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d8ab", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#41d8ab", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#4192d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d841b4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84194", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84741", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89441", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8b441", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#96d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84167", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8418d", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d641d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841ae", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d87441", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d0d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#b0d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#4f41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#5c41d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#6341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#6941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d841a1", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d85a41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d86141", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#4f41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841ce", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#a941d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d86741", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d86d41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#4fd841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d86b", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d878", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d88b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d892", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d8ab", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8bf", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#41b8d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41b2d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#41abd8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#a941d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#b041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84167", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d8bf", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841d4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d84174", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841c7", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d88141", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d878", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8cb", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#4192d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#8941d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841ba", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84194", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84187", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84167", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_pca9685_pwm_out", "name": "pca9685_pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_pwm", "name": "rgbled_pwm", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_pwm_input", "name": "pwm_input", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp101xx", "name": "icp101xx", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20689", "name": "icm20689", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_lps22hb", "name": "lps22hb", "type": "Module", "color": "#666666"}, {"id": "m_lps33hw", "name": "lps33hw", "type": "Module", "color": "#666666"}, {"id": "m_mpc2520", "name": "mpc2520", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp280", "name": "bmp280", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_bmp581", "name": "bmp581", "type": "Module", "color": "#666666"}, {"id": "m_dps310", "name": "dps310", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi055", "name": "bmi055", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_atxxxx", "name": "atxxxx", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_spa06", "name": "spa06", "type": "Module", "color": "#666666"}, {"id": "m_spl06", "name": "spl06", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_sht3x", "name": "sht3x", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#41d87b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#41d847", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#4194d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#4147d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d84174", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#aed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d88141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41d867", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#d841cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d841ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#d8419b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#4dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#417bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#bbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#94d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#cfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#5ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41b5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#8841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#c841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#419bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d87441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#d88e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#d8ae41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#8ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#81d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#41d8a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#9b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d8bb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#4167d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#ae41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d8c841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#b5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#4161d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#8e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d841c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d8418e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d86741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8d541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d89b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#41a8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d841d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d84d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#67d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#54d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#41d8c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#418ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#6141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_hygrometer", "name": "sensor_hygrometer", "type": "topic", "color": "#d5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#9bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41d894", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#b541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#d88841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8cf41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#41d861", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#416ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#6e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#bb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d841a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d874", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41d888", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d88e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#4188d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#4181d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#414dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#5a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#c241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8a841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#61d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#47d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#41d881", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#41d8b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#5441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#6741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#8141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d841c2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d841bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#c2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#7bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d86e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#4174d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#d8415a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#c8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#74d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41c2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d84188", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d89441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8c241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#88d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#6ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d8cf", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41cfd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d84194", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d84167", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8414d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d85a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d89b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#7441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#9441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_pwm_input", "name": "pwm_input", "type": "topic", "color": "#d841b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d8b541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#7b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#41d84d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#4741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#cf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84181", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#7441d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#7441d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#41c8d8", "style": "dashed"}, {"source": "m_bmp280", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_bmp581", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_dps310", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_spa06", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_spl06", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_icp101xx", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_lps22hb", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_lps33hw", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_mpc2520", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#41d881", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d841bb", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d841bb", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#a841d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#a841d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#a841d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#bb41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d89b41", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41d8ae", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#5441d8", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#414dd8", "style": "dashed"}, {"source": "m_sht3x", "target": "t_sensor_hygrometer", "color": "#d5d841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_bmi055", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_icm20689", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#d8415a", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#d841d5", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#d841d5", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#d841d5", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#d841d5", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#d841d5", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_outputs", "color": "#bb41d8", "style": "dashed"}, {"source": "m_pca9685_pwm_out", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#41d881", "style": "dashed"}, {"source": "m_pwm_input", "target": "t_pwm_input", "color": "#d841b5", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#bb41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#a8d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#c2d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#bb41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#c2d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#41d881", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d89b41", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41aed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#4167d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#c2d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#bb41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d89b41", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#54d841", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#41d861", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#41d881", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#41d8b5", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d87b41", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#cf41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#8e41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8a841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d86e", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d84d41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#d8ae41", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#6741d8", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#4174d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d8416e", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d541d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#41d8d5", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84741", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d86141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#d88841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#416ed8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#4154d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#41d861", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d8bb41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8cf41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84181", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#d84154", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#41d881", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d86e41", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#74d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#67d841", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#ae41d8", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d8417b", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#81d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#41d8cf", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d88141", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#61d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#41a8d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d8a1", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#41d8c8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#c8d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#cfd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#4dd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#4194d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#74d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#4147d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#aed841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#61d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#ae41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d8c8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41d894", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#9bd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#94d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41d867", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#d84141", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41d888", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#b5d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d8c841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8bb", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#41d84d", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41a1d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#6ed841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#a1d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#8ed841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#d88e41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8a841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#74d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#7b41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#41d8c2", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#8841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#9441d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d85441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#a841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#ae41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41bbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#c841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#cf41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#5ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d841d5", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#d841cf", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#419bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#4181d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#417bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#41d854", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#4161d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41d85a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#41d867", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#41d861", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#d8419b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#4154d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d84194", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#414dd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#41d881", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d8418e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d8b541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d8bb41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#41d8a8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d84174", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#4741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41d8ae", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#d8415a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#5a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8414d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#6e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8bb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d84147", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#ae41d8", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d8417b", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#c841d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#8141d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d86741", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d86e41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#bbd841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#ae41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#41d8c2", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#88d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41b5d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#47d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#41d847", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#4181d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#4174d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d841a8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#415ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#4154d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8a841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d874", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d88e", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d8c841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#4141d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#4741d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#8ed841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#c841d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d87441", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#9b41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#d88841", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#418ed8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d89441", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#a841d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#a141d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#6141d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d8b541", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4d41d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d841c8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d841c2", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#bb41d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d84167", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41d8ae", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d85a41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d841ae", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#41d5d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#41c2d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d87b", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d8b541", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#4188d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d8a141", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#d8c241", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#b541d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d87441", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#9b41d8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#c841d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#c241d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#c841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#61d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d89b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8d541", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d8c8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d841a1", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#9b41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d87441", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#7bd841", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41cfd8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d84188", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#c241d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d841c2", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8a841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#d88e41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#4d41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d841c2", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#41d888", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#74d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#c241d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#414dd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41c2d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41cfd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41cfd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41cfd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41cfd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_pwm", "color": "#41cfd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_atxxxx", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_atxxxx", "color": "#d8bb41", "style": "normal"}, {"source": "t_battery_status", "target": "m_atxxxx", "color": "#41d881", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#54d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d8a841", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#41d881", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#7b41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d8bb41", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#4174d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pca9685_pwm_out", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pca9685_pwm_out", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pca9685_pwm_out", "color": "#d88e41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pca9685_pwm_out", "color": "#4d41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pca9685_pwm_out", "color": "#d841c2", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pca9685_pwm_out", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pca9685_pwm_out", "color": "#41d888", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pca9685_pwm_out", "color": "#74d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pca9685_pwm_out", "color": "#c241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#81d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8a841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#d88e41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#4d41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d841c2", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#41d888", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#74d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#c241d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#a8d841", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#d88e41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#4d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8a841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d841c2", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#41d888", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#74d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d8a841", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#c241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#41d881", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#7441d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8a841", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#c241d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d841c2", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#41d861", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d8a841", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d8bb41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#41d881", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d8b541", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d89b41", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#4174d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d84188", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#8841d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41cfd8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41bbd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#7bd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#74d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#c241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#67d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#d88e41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d841c2", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#419bd8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#4174d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8a841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#414dd8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d8418e", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#41d888", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d8bb41", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#d84188", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d8c841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d8416e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#4d41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d8c841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d8a1", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8a841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d84741", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#81d841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d87441", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d8b541", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#41d8a8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d85441", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d8bb41", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#7441d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#81d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#4154d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d841bb", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41d867", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#a1d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#8ed841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#41c8d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d84d41", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41c2d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#a841d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d85a41", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#b541d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#c241d8", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#cf41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#d88841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#54d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#d88e41", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#47d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d841c2", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#418ed8", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d89b41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#4188d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#41d84d", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#4174d8", "style": "normal"}, {"source": "t_pwm_input", "target": "m_commander", "color": "#d841b5", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#416ed8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#4161d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d841a8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8a841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d874", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d8bb41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d89b", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8d541", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84181", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d84167", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41d8ae", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4d41d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#c2d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#d84154", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#6141d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#6e41d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#61d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#8ed841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#8e41d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#9b41d8", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#d8ae41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d87441", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#4181d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#41d8a8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#54d841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#d88841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8a841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#4188d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d89441", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#a141d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#6141d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d8b541", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#c241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#81d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d89b41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8a841", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#41d881", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#6741d8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#41d84d", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#c841d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#8141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d8c841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d8417b", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#54d841", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#cfd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8a841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#61d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d8c841", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84181", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d88141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#54d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d8a841", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#4dd841", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#aed841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d8c841", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84181", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#54d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#4154d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d8a841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d86741", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#41b5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d8c841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d541d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#54d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#ae41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d8c841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#5ad841", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d84174", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#41d861", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41d867", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#88d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41b5d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#417bd8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#c241d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41c2d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8a841", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8c241", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#b541d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41b5d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#8141d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#d88841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#54d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d8a1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#4154d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8a841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d841c2", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#418ed8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d87441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#41d861", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#d8415a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d8bb41", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41d85a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8a841", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8a841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d85a41", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#a1d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8a841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#8ed841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d85a41", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d87441", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#d88841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#d88e41", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8414d", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d89441", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d89b41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d8a141", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8a841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d8b541", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8cf41", "style": "normal"}, {"source": "t_sensor_hygrometer", "target": "m_mavlink", "color": "#d5d841", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#c8d841", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#b5d841", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#9bd841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#94d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#8ed841", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#6ed841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#5ad841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#54d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#47d841", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#41d84d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#41d861", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#41d867", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d86e", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d874", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#41d87b", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#41d881", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41d894", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d89b", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41d8ae", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#41d8b5", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8bb", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#41d8c2", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d8cf", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#41d8d5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41b5d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#41a8d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#418ed8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#4188d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#4174d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#416ed8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#4167d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#415ad8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#4154d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#414dd8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#4741d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#5441d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#5a41d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#6741d8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#9441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#8e41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#a841d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#ae41d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#bb41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#b541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#c841d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#cf41d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d841c8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d841c2", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d841bb", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d841ae", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d84194", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84181", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d84167", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#d84154", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#7b41d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d8c841", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#9b41d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#bbd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d86e41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d8c841", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d541d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#ae41d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#41d881", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d8c841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84181", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#41d8c2", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8bb", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#4741d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#4154d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#4141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8a841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41d841", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#4194d8", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d88e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d8bb41", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#4174d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#c241d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#7b41d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#41d854", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#c841d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#4154d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#41d861", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d86741", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41b5d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#7441d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#d88841", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d841d5", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#8e41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#b541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41c2d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d89441", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#d84154", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#a841d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d85a41", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#418ed8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8c241", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#67d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#d88e41", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4d41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d841c2", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#7bd841", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41d888", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#74d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d8a141", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8a141", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8a141", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d841c8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#bb41d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d84167", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41c2d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d85a41", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8c241", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#c241d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#c841d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#d88e41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#ae41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#41d861", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d86741", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d89b", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#a1d841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d8cf", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#8e41d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41b5d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#c241d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#54d841", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d841cf", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#4174d8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d8419b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#41d861", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d8bb41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d8c841", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84161", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v5x.json b/docs/public/middleware/graph_px4_fmu-v5x.json index 9b12ca438646..cd5dbf7280a1 100644 --- a/docs/public/middleware/graph_px4_fmu-v5x.json +++ b/docs/public/middleware/graph_px4_fmu-v5x.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_hardfault_stream", "name": "hardfault_stream", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#418dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#9ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#84d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#9e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#a541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#a5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#4173d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d873", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#8441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_battery_info", "name": "battery_info", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d88d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d87541", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d88241", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_info", "color": "#d88f41", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_info", "color": "#d88f41", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d87541", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#7e41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8a941", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d89c41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8a941", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#98d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#91d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#8bd841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d880", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d886", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#4180d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#416cd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841b6", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8b041", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8c441", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#b2d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#abd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#a5d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#9ed841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#6a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d341d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841b0", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d8418f", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84147", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d89a", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#9e41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841bd", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d8a1", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88941", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#63d841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#8b41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#84d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#7ed841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#77d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#71d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#6ad841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d89a", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d8ae", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d8b4", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8c8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#4193d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#418dd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#7741d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84182", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#6ad841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#7741d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#49d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#43d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d84b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d852", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d866", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d86c", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41c1d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d873", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4152d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#41d893", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d84196", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8a7", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8b641", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8c1", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#bf41d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d89a", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8ce", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8d5", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d8a341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8bd41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#98d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#5dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d845", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d859", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d85f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d873", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d893", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8a7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d5d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41ced8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41b4d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#41a7d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41a1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#419ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#4173d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#9141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#9e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#a541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d8418f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84154", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88941", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#8441d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#9e41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d1", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841bd", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84182", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84e41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8bd41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#bfd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#56d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#50d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d886", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41ced8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41c8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41bbd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#4186d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#4166d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#415fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#a541d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841b0", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d84196", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8416e", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d879", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d86141", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#4179d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#4159d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8d5", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#4159d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d88d", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#5d41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#6a41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#7141d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a3", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d8419c", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#cc41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d841d7", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841a9", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d84189", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#4941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#6341d8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d86e41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_battery_info", "color": "#d88f41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d8bb", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41aed8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#4159d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#ab41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#b941d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841ca", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#6ad841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#7741d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#9841d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d1", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841c4", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87b41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#b2d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#a5d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#63d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d8b4", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84161", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d87541", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d84168", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d87541", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d841ca", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8a941", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d8418f", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84741", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8b641", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#ccd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#b9d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#b2d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#a5d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#9ed841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#98d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#56d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d886", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8c1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8ce", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8d5", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41c8d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41bbd8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41b4d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#4180d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#415fd8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#4159d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#5d41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#6a41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#7141d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#7e41d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84168", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#8bd841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#6ad841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8d5", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#7741d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#9841d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d8415b", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#d84168", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8bd41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#49d841", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d89a", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d8a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d88241", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#c6d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8a7", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d8b4", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#6a41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84154", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#b9d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d84168", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84168", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d88241", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#71d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d88241", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#7ed841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#77d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#6ad841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8ae", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d88241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8ce", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#4186d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89641", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8b041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d89641", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d845", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d859", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d85f", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8ce", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8416e", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d873", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84168", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_hardfault_stream", "color": "#9141d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#414bd8", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#d87b41", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d89641", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#b9d841", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#41d886", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d84168", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d84168", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#63d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d88241", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d8b4", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#4186d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#6a41d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#8441d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84161", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d8418f", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d84168", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8ce", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84168", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_battery_info", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d8b641", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8c441", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d141", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d741", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#a5d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#98d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#91d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#84d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#56d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d852", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d873", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d886", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d88d", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8a7", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8ce", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8d5", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41ced8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41c8d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41c1d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#4186d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#416cd8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#5d41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#6a41d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#8b41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#a541d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d84189", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8415b", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d8418f", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89641", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8b041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d89641", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d886", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d88d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d84168", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8c441", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#50d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d886", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8a7", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41ced8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#418dd8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#4166d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#49d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d89a", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d8a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#49d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d89a", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d8a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#49d841", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#41d879", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d89a", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d8a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8ce", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d84168", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d87541", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d84168", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d88d", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8d5", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#4173d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d8bb", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d8bb", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d8bb", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d8bb", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84741", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89641", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8b641", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#91d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d84189", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841a9", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d87541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#ccd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#abd841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#5d41d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#6341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#6a41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d8419c", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d86141", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841ca", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#ab41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d86e41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#49d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d873", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#41d879", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d886", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d89a", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d8a1", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d8bb", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8ce", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#41a7d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41a1d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#419ad8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#ab41d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841c4", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d88241", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#5dd841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d886", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d5d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#4186d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84168", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_frsky_telemetry", "name": "frsky_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_hott_telemetry", "name": "hott_telemetry", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_batt_smbus", "name": "batt_smbus", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16448", "name": "adis16448", "type": "Module", "color": "#666666"}, {"id": "m_adis16507", "name": "adis16507", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_thoneflow", "name": "thoneflow", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_paa3905", "name": "paa3905", "type": "Module", "color": "#666666"}, {"id": "m_paw3902", "name": "paw3902", "type": "Module", "color": "#666666"}, {"id": "m_pmw3901", "name": "pmw3901", "type": "Module", "color": "#666666"}, {"id": "m_px4flow", "name": "px4flow", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_crsf_rc", "name": "crsf_rc", "type": "Module", "color": "#666666"}, {"id": "m_ghst_rc", "name": "ghst_rc", "type": "Module", "color": "#666666"}, {"id": "m_sbus_rc", "name": "sbus_rc", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_irlock", "name": "irlock", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_dsm_rc", "name": "dsm_rc", "type": "Module", "color": "#666666"}, {"id": "m_batmon", "name": "batmon", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "m_bst", "name": "bst", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#b7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d89d41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d8b141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#96d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#9641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#4190d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#41d8d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d89041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#417cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#d86f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d8aa41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#d84190", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#62d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#41d2d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#d8b741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#419dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#aa41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#cbd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#89d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#41bed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41a3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#68d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#4741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#5b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#d8cb41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#5bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41aad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#4196d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#4e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#6241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d8419d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#82d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#b741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d86f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d8aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#41d8be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#9d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#cb41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d841b1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#7541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#a341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841d2", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d8b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#4182d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#4154d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#6f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#47d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d882", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41cbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#41d868", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#41d89d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41d8b1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#d841cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#d8d241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d896", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#7c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#b141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d841aa", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#41d85b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d87c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#41d889", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#41d890", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#41b1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#5441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#6841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#aad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#4ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#41d847", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#41d862", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#415bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#4147d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#8241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#9041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d841be", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d8416f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d8be41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#c4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#9dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#4189d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#d8417c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#7cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#6fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#c441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d841b7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d86241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#b1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#a3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#54d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#416fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#4168d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d87c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#75d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#41b7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#4162d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#d84162", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#90d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d8cb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#8941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#41d854", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#4162d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#4162d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#d85b41", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d8414e", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d8414e", "style": "dashed"}, {"source": "m_batt_smbus", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#415bd8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#415bd8", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#9d41d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#9d41d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#9d41d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#4ed841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d87c41", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d841aa", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#41d889", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#6841d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#41b7d8", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#9041d8", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_adis16448", "target": "t_sensor_baro", "color": "#d8414e", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_adis16507", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_irlock", "target": "t_irlock_report", "color": "#9dd841", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_paa3905", "target": "t_sensor_optical_flow", "color": "#4154d8", "style": "dashed"}, {"source": "m_paw3902", "target": "t_sensor_optical_flow", "color": "#4154d8", "style": "dashed"}, {"source": "m_pmw3901", "target": "t_sensor_optical_flow", "color": "#4154d8", "style": "dashed"}, {"source": "m_px4flow", "target": "t_sensor_optical_flow", "color": "#4154d8", "style": "dashed"}, {"source": "m_thoneflow", "target": "t_sensor_optical_flow", "color": "#4154d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#4ed841", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d841aa", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#41d889", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#4ed841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#c441d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#c4d841", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d841aa", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#41d889", "style": "dashed"}, {"source": "m_crsf_rc", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_dsm_rc", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_ghst_rc", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_sbus_rc", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#c4d841", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_batmon", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_hott_telemetry", "target": "t_esc_status", "color": "#d87c41", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#4ed841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#5b41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d87c41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#c4d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#82d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d841aa", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#41d889", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#47d841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#41d847", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841d2", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#4ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#d8417c", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#414ed8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#4147d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#41d854", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#8241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41cbd8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d841d8", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41aad8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#7541d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#41d889", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#4741d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d2d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#b741d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d85441", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d86841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d89641", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d841a3", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8a341", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d8419d", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d86f", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d896", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d84147", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d241d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#6f41d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d8c441", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d882", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d8d2", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#4168d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#d8cb41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#d84182", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#d841b7", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#d84175", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#41d2d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#4141d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#41c4d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#41d868", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#41bed8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#d241d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#417cd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#4e41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#9641d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#41c4d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#41d868", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#d841cb", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#d8b741", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#aa41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#d88941", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d8aa", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#be41d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d89041", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#cb41d8", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#4182d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d88241", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d84168", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d86241", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#4196d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8a3", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#41d862", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#8241d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#9dd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#b141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#90d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#89d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#b741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#d84741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d86841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#41b7d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#41b1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#68d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41a3d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#62d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#5bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#d86f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#4190d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#4189d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#4182d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d89041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d841b1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d8419d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#4175d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#d84190", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#4154d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#41d854", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d8416f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#41d890", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#cbd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#6841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#6f41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#bed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#41d8be", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#b1d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#7c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d8cb", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#8941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d8414e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#9d41d8", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#41d8d2", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d8c441", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#89d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#6f41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#aad841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84154", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#419dd8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#d84741", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#75d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#cb41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#54d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d841c4", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d841be", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d8419d", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d8b141", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#d8417c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d87c", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#5441d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#41d89d", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#d8d241", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#8241d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#8941d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#d87541", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#4196d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d8415b", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d896", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#90d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#41d8c4", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d875", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#a3d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#9d41d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#a341d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#4ed841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d841aa", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#41d889", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d8414e", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#41b7d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#d84162", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#41d84e", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#90d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#96d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#7cd841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#b7d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d89d41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d8aa41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41d8b1", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#41d85b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d84196", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d84189", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#6241d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#89d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d8b7", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#41d8d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#41c4d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#41d868", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d8be41", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#416fd8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#6fd841", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#b741d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#8241d8", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d8b141", "style": "normal"}, {"source": "t_gripper", "target": "m_dshot", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#4ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#7541d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d882", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#41d889", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#6841d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#7cd841", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#416fd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#416fd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#416fd8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#416fd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#47d841", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#d8417c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#b741d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#8241d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d8cb", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d8419d", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#8241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#d8cb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#8241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#d8cb41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#8241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#d8cb41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#4ed841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#4ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#7541d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d882", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#41d889", "style": "normal"}, {"source": "t_gripper", "target": "m_px4io", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#4ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#be41d8", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#c441d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#8241d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#d241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d882", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#41d889", "style": "normal"}, {"source": "t_battery_status", "target": "m_crsf_rc", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_crsf_rc", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_crsf_rc", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dsm_rc", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_dsm_rc", "color": "#8241d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_ghst_rc", "color": "#d8416f", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#41d85b", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#4ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_bst", "color": "#d86841", "style": "normal"}, {"source": "t_battery_status", "target": "m_bst", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_frsky_telemetry", "color": "#b741d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_frsky_telemetry", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_frsky_telemetry", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_frsky_telemetry", "color": "#d8419d", "style": "normal"}, {"source": "t_home_position", "target": "m_hott_telemetry", "color": "#d8417c", "style": "normal"}, {"source": "t_esc_status", "target": "m_hott_telemetry", "color": "#d87c41", "style": "normal"}, {"source": "t_airspeed", "target": "m_hott_telemetry", "color": "#90d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_hott_telemetry", "color": "#d8416f", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#6fd841", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#b741d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#cb41d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d241d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#68d841", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#6fd841", "style": "normal"}, {"source": "t_gripper", "target": "m_uavcan", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#4ed841", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#416fd8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d8be41", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#d8417c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#41d85b", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d882", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#41d889", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8a3", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#cbd841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#6841d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#41d8be", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#7541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#8241d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#4168d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#b741d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#6241d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#90d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#cb41d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d86841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#4e41d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#d8cb41", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#4162d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#8241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#d8cb41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d86841", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#415bd8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d8419d", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d89041", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#b741d8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#7cd841", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#d85b41", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#cb41d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41cbd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d86841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#41b7d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#4196d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#4ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#47d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d87c41", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d88241", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d841be", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d841b1", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d8419d", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d84196", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#41d84e", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#d8417c", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#41d85b", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#41d862", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#41d854", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#d84162", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d84168", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d86f", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d875", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d87c", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#41d889", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d896", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#41d89d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8a3", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#d8d241", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#c4d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d8b7", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41d8b1", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#7c41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#8241d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#41d8c4", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#9d41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d84189", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#4196d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#6241d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#41d8d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#8241d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#41c4d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#41d868", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41aad8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8d841", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#5bd841", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d8415b", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d896", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#47d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#90d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#4182d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#cb41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#41d8c4", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#a3d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d87c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#8241d8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#d8cb41", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d88241", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#41d85b", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#8241d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#aad841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841d2", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#41d8d2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#47d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#8241d8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#41bed8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d86841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841d2", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#47d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d86841", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d84175", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d2d8", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#4141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#41c4d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#8241d8", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#417cd8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841d2", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#d841c4", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#47d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d86841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#8241d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d8419d", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#47d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#8241d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#4741d8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#62d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d841c4", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#4190d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d89041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#41d85b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d8419d", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41a3d8", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#54d841", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41d8b1", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#7cd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#8241d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#41d84e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841d2", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d896", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#4ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#47d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#6241d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d8419d", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#aad841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#b741d8", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#9dd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#41d85b", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#8241d8", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#41b1d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#8241d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#d84162", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#41d862", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#4196d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d85441", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d86241", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d86841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d87c41", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d89041", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d89d41", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d8aa41", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#d8b741", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d2d841", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#bed841", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#b7d841", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#b1d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#a3d841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#96d841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#89d841", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#90d841", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#82d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#4ed841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#47d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#41d847", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#41d854", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#41d85b", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#41d86f", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d87c", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#41d890", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#41d896", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#41d89d", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d8aa", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41d8b1", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d8b7", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d8cb", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#41d8d2", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#41b7d8", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41a3d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#4196d8", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#4189d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#4182d8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#4175d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#4168d8", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#415bd8", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#414ed8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#4147d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#5b41d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#6241d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#6841d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#8241d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#9041d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#8941d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#9d41d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#a341d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#aa41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#cb41d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d841d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#d841cb", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841d2", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d841be", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d841b7", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d841aa", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d8419d", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d84182", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#d8417c", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d8416f", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#d84162", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84154", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841d2", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#41d8d2", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#89d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d86841", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#419dd8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d84189", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#b741d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#6f41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841d2", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8a3", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d8416f", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#8241d8", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#4741d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#d84741", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#d8417c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#b741d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d2d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#41d85b", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#4182d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#cb41d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#75d841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d8419d", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#5441d8", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#8941d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#9641d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#41d85b", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#b141d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d8cb", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#4196d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841d2", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d896", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#41d84e", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#4162d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#4154d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41d8b1", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#7cd841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#d84162", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d86f", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d875", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#a3d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#9d41d8", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#d87541", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#4ed841", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d8be41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8a3", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#be41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#41d85b", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#7541d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d241d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d882", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#41d889", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d89d41", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#96d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d89d41", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8aa41", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d89d41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#a341d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d841aa", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#41d84e", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#7cd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#41d85b", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#d84162", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d8b7", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#cb41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d86841", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d86f41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841d2", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d841c4", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#47d841", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d84190", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#4168d8", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#d8417c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#41d85b", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#41d862", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#8241d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84154", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_fmu-v6x.json b/docs/public/middleware/graph_px4_fmu-v6x.json index c102aaa60af3..7beaf21d0ac2 100644 --- a/docs/public/middleware/graph_px4_fmu-v6x.json +++ b/docs/public/middleware/graph_px4_fmu-v6x.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_hardfault_stream", "name": "hardfault_stream", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#bed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#4183d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d867", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#73d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d8b3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#57d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#4160d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#7ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d860", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d853", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d85a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#b0d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#6cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d84c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#419ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#417cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841c9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8ae41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41a5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#a941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#c541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#87d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#5ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d8b9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84163", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#9cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d8418c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84177", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#a9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d86e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41acd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#4197d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d84193", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#4190d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#80d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8ac", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#7341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#b041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841bc", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841b5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d87e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d8a5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#4175d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#8041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#b741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d8419a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d875", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41b9d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4153d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#5741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#8741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8c341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#a3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41b3d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#4167d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#7a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#a341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d841d0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8bc41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#c5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#4ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d87c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841c3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d89a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8a741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#8ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#65d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41c0d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#9541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d8a041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d883", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d88a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d897", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8c7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#414cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_battery_info", "name": "battery_info", "type": "topic", "color": "#d88c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d89e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#418ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#416ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#8e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#be41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8c941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#41d8c0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#4a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#6541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#9c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d84170", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#d87041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#b7d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#415ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#5e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#6c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d890", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8b541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41c7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#95d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d86a41", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_ads1115", "target": "t_adc_report", "color": "#d87041", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d87e41", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#4a41d8", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#d87041", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#8e41d8", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8a741", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d89a41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8a741", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d86a41", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#95d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#8ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#87d841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d883", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d88a", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#4175d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#4160d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841ae", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d8416a", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86341", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8ae41", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8c341", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#d85c41", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#d86a41", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#b7d841", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#b0d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#a9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#a3d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#9cd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#7a41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d841d0", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841a7", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d8418c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417e", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84147", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d89e", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#b041d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841b5", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d8a5", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84177", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88541", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#5ed841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#9c41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#80d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#7ad841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#73d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#6cd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#65d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d89e", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d8b3", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d8b9", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8ce", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#418ad8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#4183d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#8741d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84185", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#65d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#8741d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84177", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#43d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#41d845", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d853", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d85a", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d86e", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d875", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41b9d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d87c", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4145d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#5e41d8", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#4a41d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d84193", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8ac", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8b541", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8c7", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d341d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d89e", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8d5", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d5d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d8416a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d8a041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8bc41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8c941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#95d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#57d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#41d845", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d84c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d860", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d867", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d87c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d890", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d897", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8ac", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41ced8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41c7d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41acd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#419ed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#4197d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#4190d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#4167d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#4341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#4a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#5e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#6541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#7341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#a341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#b041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#b741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#c541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#d841d7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d841d0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841c9", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841a7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d8418c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84177", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84155", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84177", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88541", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#9541d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#b041d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c9", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841b5", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84185", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84e41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84177", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#4a41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8bc41", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#bed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#50d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#4ad841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d88a", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41c7d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41c0d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41b3d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#417cd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#415ad8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4153d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#b741d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841a7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d84193", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d84170", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d8416a", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#d85c41", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#d86a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#d85c41", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#d86a41", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#41d890", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#416ed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#414cd8", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#41d890", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d5d8", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#6c41d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#414cd8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87741", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#5041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#7a41d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#8041d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a0", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d8419a", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#41d87c", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#4145d8", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#5e41d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#5741d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#d85541", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#d85c41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#d86a41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_battery_info", "color": "#d88c41", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#b7d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#41d8c0", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41a5d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#414cd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#be41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#cc41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841c3", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#c5d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#65d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#8741d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#a941d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841c9", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841bc", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84163", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415c", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87741", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#b0d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#a3d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#5ed841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d8b9", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84163", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#d87041", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#d8416a", "style": "normal"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#d87041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d841c3", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8a741", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d8418c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#d84741", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85541", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d87e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89341", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8b541", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#ccd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#c5d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#b7d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#b0d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#a9d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#a3d841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#9cd841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#95d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#50d841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d88a", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8c7", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8d5", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d5d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41c0d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41b3d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41acd8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#4175d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4153d8", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#414cd8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#5741d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#5e41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#6541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#6c41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#7a41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#8041d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#8e41d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#a341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d8416a", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#87d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#65d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d5d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#8741d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#a941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d8415c", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8bc41", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d86341", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#d86a41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#43d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#41d89e", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#41d8a5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d841c3", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d87e41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#c5d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8ac", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d8b9", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#7a41d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#8041d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#b7d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#d8416a", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#9541d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d8416a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d87e41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#6cd841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d8416a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d8416a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d87e41", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#7ad841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#73d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#65d841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8b3", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d8416a", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d87e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8d5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#417cd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#b041d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d8416a", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d87e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89341", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8ae41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d8416a", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#41d845", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d84c", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d860", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d867", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8d5", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#417cd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d84170", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d87c", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#5741d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#6541d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d8416a", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_hardfault_stream", "color": "#a341d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#d8416a", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#d8416a", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#d8416a", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#5ed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#d8416a", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d87e41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d8b9", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#417cd8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#7a41d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#9541d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#b041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84163", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d897", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d8418c", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#bed841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#d8416a", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89341", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8d5", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d8416a", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d8416a", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d8416a", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d85c41", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d87e41", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88541", "style": "normal"}, {"source": "t_battery_info", "target": "m_mavlink", "color": "#d88c41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89341", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d89a41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d8a041", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8a741", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d8b541", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8c341", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8c941", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d041", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d741", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#c5d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#b7d841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#b0d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#a9d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#a3d841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#95d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#8ed841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#80d841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#50d841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d84c", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41d853", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d85a", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d86e", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d875", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d87c", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d883", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d88a", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d890", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8ac", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8d5", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41c7d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41c0d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41b9d8", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41a5d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#418ad8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#417cd8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#4160d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4153d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#5741d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#5e41d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#6c41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#7a41d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#9c41d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#b741d8", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841bc", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d8419a", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417e", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84163", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841c9", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d8416a", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8415c", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#b041d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841b5", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d8418c", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89341", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8ae41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84177", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d8416a", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d87e41", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d89341", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d88a", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d890", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d8416a", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8c341", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#4ad841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d88a", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8ac", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41c7d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#4183d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#415ad8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#b741d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841a7", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d8416a", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84147", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d86341", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#d86a41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#43d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#41d89e", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#41d8a5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d841c3", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d86341", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#d86a41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#43d841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#41d89e", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#41d8a5", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8d5", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#416ed8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#d8416a", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#d87041", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#d8416a", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d890", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d5d8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#4167d8", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#41d8c0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#41d8c0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#41d8c0", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#41d8c0", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#d84741", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89341", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8b541", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#8ed841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d8416a", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#d87041", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#ccd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#a9d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#5741d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#6541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#6c41d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#7341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#7a41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a0", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d8419a", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#41d87c", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#4a41d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#6541d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#6c41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841c3", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#be41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#d85541", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d86341", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#d86a41", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#43d841", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#41d87c", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d88a", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#41d89e", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#41d8a5", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#41d8c0", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8d5", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#419ed8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#4197d8", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#4190d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#be41d8", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#c541d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841bc", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d87e41", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#57d841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d88a", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41ced8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#417cd8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#9c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d841d0", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841c3", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841ae", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84185", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d8416a", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_serial", "name": "lightware_laser_serial", "type": "Module", "color": "#666666"}, {"id": "m_pm_selector_auterion", "name": "pm_selector_auterion", "type": "Module", "color": "#666666"}, {"id": "m_lightware_laser_i2c", "name": "lightware_laser_i2c", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_is31fl3195", "name": "rgbled_is31fl3195", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_cdcacm_autostart", "name": "cdcacm_autostart", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_ncp5623c", "name": "rgbled_ncp5623c", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_capture", "name": "camera_capture", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_ulanding_radar", "name": "ulanding_radar", "type": "Module", "color": "#666666"}, {"id": "m_battery_status", "name": "battery_status", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_rgbled_lp5562", "name": "rgbled_lp5562", "type": "Module", "color": "#666666"}, {"id": "m_safety_button", "name": "safety_button", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_i2c_launcher", "name": "i2c_launcher", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_esc_battery", "name": "esc_battery", "type": "Module", "color": "#666666"}, {"id": "m_led_control", "name": "led_control", "type": "Module", "color": "#666666"}, {"id": "m_teraranger", "name": "teraranger", "type": "Module", "color": "#666666"}, {"id": "m_septentrio", "name": "septentrio", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_board_adc", "name": "board_adc", "type": "Module", "color": "#666666"}, {"id": "m_ms5525dso", "name": "ms5525dso", "type": "Module", "color": "#666666"}, {"id": "m_adis16470", "name": "adis16470", "type": "Module", "color": "#666666"}, {"id": "m_icm42670p", "name": "icm42670p", "type": "Module", "color": "#666666"}, {"id": "m_icm42688p", "name": "icm42688p", "type": "Module", "color": "#666666"}, {"id": "m_lsm303agr", "name": "lsm303agr", "type": "Module", "color": "#666666"}, {"id": "m_mmc5983ma", "name": "mmc5983ma", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_icp201xx", "name": "icp201xx", "type": "Module", "color": "#666666"}, {"id": "m_ms4525do", "name": "ms4525do", "type": "Module", "color": "#666666"}, {"id": "m_icm20602", "name": "icm20602", "type": "Module", "color": "#666666"}, {"id": "m_icm20649", "name": "icm20649", "type": "Module", "color": "#666666"}, {"id": "m_icm20948", "name": "icm20948", "type": "Module", "color": "#666666"}, {"id": "m_icm45686", "name": "icm45686", "type": "Module", "color": "#666666"}, {"id": "m_iim42652", "name": "iim42652", "type": "Module", "color": "#666666"}, {"id": "m_qmc5883l", "name": "qmc5883l", "type": "Module", "color": "#666666"}, {"id": "m_vcm1193l", "name": "vcm1193l", "type": "Module", "color": "#666666"}, {"id": "m_rc_input", "name": "rc_input", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_ads1115", "name": "ads1115", "type": "Module", "color": "#666666"}, {"id": "m_cm8jl65", "name": "cm8jl65", "type": "Module", "color": "#666666"}, {"id": "m_tf02pro", "name": "tf02pro", "type": "Module", "color": "#666666"}, {"id": "m_vl53l0x", "name": "vl53l0x", "type": "Module", "color": "#666666"}, {"id": "m_vl53l1x", "name": "vl53l1x", "type": "Module", "color": "#666666"}, {"id": "m_ak09916", "name": "ak09916", "type": "Module", "color": "#666666"}, {"id": "m_hmc5883", "name": "hmc5883", "type": "Module", "color": "#666666"}, {"id": "m_ist8308", "name": "ist8308", "type": "Module", "color": "#666666"}, {"id": "m_ist8310", "name": "ist8310", "type": "Module", "color": "#666666"}, {"id": "m_lis3mdl", "name": "lis3mdl", "type": "Module", "color": "#666666"}, {"id": "m_iis2mdc", "name": "iis2mdc", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out", "name": "pwm_out", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_bmp388", "name": "bmp388", "type": "Module", "color": "#666666"}, {"id": "m_ms5611", "name": "ms5611", "type": "Module", "color": "#666666"}, {"id": "m_ll40ls", "name": "ll40ls", "type": "Module", "color": "#666666"}, {"id": "m_tfmini", "name": "tfmini", "type": "Module", "color": "#666666"}, {"id": "m_heater", "name": "heater", "type": "Module", "color": "#666666"}, {"id": "m_bmi088", "name": "bmi088", "type": "Module", "color": "#666666"}, {"id": "m_rgbled", "name": "rgbled", "type": "Module", "color": "#666666"}, {"id": "m_ak8963", "name": "ak8963", "type": "Module", "color": "#666666"}, {"id": "m_bmm150", "name": "bmm150", "type": "Module", "color": "#666666"}, {"id": "m_rm3100", "name": "rm3100", "type": "Module", "color": "#666666"}, {"id": "m_ina226", "name": "ina226", "type": "Module", "color": "#666666"}, {"id": "m_ina228", "name": "ina228", "type": "Module", "color": "#666666"}, {"id": "m_ina238", "name": "ina238", "type": "Module", "color": "#666666"}, {"id": "m_uavcan", "name": "uavcan", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_sdp3x", "name": "sdp3x", "type": "Module", "color": "#666666"}, {"id": "m_dshot", "name": "dshot", "type": "Module", "color": "#666666"}, {"id": "m_px4io", "name": "px4io", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_distance_sensor_mode_change_request", "name": "distance_sensor_mode_change_request", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41d84e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#4185d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41bdd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#41a8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#4147d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#4171d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#4141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#415cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#8c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#93d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#55d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41d855", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#41d878", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#41d8bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_operator_id", "name": "open_drone_id_operator_id", "type": "topic", "color": "#417fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#bd41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d89a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_arm_status", "name": "open_drone_id_arm_status", "type": "topic", "color": "#41d87f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_uavcan_parameter_request", "name": "uavcan_parameter_request", "type": "topic", "color": "#9341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d8af41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#41d85c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#41d86a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d885", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41cad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#4741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#5c41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_uavcan_parameter_value", "name": "uavcan_parameter_value", "type": "topic", "color": "#c4d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#41d863", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#4178d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_self_id", "name": "open_drone_id_self_id", "type": "topic", "color": "#d88541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#b6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#78d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#4163d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#8541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#d841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d87141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_open_drone_id_system", "name": "open_drone_id_system", "type": "topic", "color": "#bdd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#a841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d847", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d88c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#7841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#a141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#af41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#9ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#4ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#41d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#d141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#d84171", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#d84163", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d85c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#8cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#5cd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41b6d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d841a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#85d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#47d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#5541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d84193", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d8418c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d85541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#afd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#41d8ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#4e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#9a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#ca41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d84155", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d8a141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#41d8af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#41afd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#416ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#7f41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d84185", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84178", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#d8416a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d8415c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#d88c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#7fd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d8a8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#41d8b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#b641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_safety_button", "name": "safety_button", "type": "topic", "color": "#d841af", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#d841a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#cad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#41d871", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#418cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_px4io_status", "name": "px4io_status", "type": "topic", "color": "#414ed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#c441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#d86a41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d87841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d87f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#41d8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_led_control", "name": "led_control", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#d8419a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#d86341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#d8a841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_adc_report", "name": "adc_report", "type": "topic", "color": "#a8d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#a1d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d8417f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#4155d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#41c4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}], "links": [{"source": "m_ads1115", "target": "t_adc_report", "color": "#a8d841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_system_power", "color": "#cad841", "style": "dashed"}, {"source": "m_board_adc", "target": "t_adc_report", "color": "#a8d841", "style": "dashed"}, {"source": "m_bmp388", "target": "t_sensor_baro", "color": "#d87841", "style": "dashed"}, {"source": "m_icp201xx", "target": "t_sensor_baro", "color": "#d87841", "style": "dashed"}, {"source": "m_ms5611", "target": "t_sensor_baro", "color": "#d87841", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_camera_trigger", "color": "#d8c441", "style": "dashed"}, {"source": "m_camera_capture", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8c441", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_ms4525do", "target": "t_differential_pressure", "color": "#8541d8", "style": "dashed"}, {"source": "m_ms5525dso", "target": "t_differential_pressure", "color": "#8541d8", "style": "dashed"}, {"source": "m_sdp3x", "target": "t_differential_pressure", "color": "#8541d8", "style": "dashed"}, {"source": "m_cm8jl65", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_lightware_laser_i2c", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_lightware_laser_serial", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_ll40ls", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_teraranger", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_tf02pro", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_tfmini", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_ulanding_radar", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_vl53l0x", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_vl53l1x", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_outputs", "color": "#41d893", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_armed", "color": "#7f41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_dshot", "target": "t_actuator_motors", "color": "#ca41d8", "style": "dashed"}, {"source": "m_dshot", "target": "t_esc_status", "color": "#d84147", "style": "dashed"}, {"source": "m_septentrio", "target": "t_gps_inject_data", "color": "#d84141", "style": "dashed"}, {"source": "m_septentrio", "target": "t_satellite_info", "color": "#d8415c", "style": "dashed"}, {"source": "m_septentrio", "target": "t_sensor_gps", "color": "#d86341", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d84141", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#d86341", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d8415c", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_adis16470", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_bmi088", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_icm20602", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_icm20649", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_icm20948", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_icm42670p", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_icm42688p", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_icm45686", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_iim42652", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_ak09916", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_ak8963", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_bmm150", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_hmc5883", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_ist8308", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_ist8310", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_lis3mdl", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_lsm303agr", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_mmc5983ma", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_qmc5883l", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_rm3100", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_iis2mdc", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_vcm1193l", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_ina226", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_ina228", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_ina238", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_outputs", "color": "#41d893", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_armed", "color": "#7f41d8", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_pwm_out", "target": "t_actuator_motors", "color": "#ca41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_outputs", "color": "#41d893", "style": "dashed"}, {"source": "m_px4io", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_px4io", "target": "t_safety_button", "color": "#d841af", "style": "dashed"}, {"source": "m_px4io", "target": "t_px4io_status", "color": "#414ed8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_armed", "color": "#7f41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_px4io", "target": "t_actuator_motors", "color": "#ca41d8", "style": "dashed"}, {"source": "m_px4io", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_px4io", "target": "t_input_rc", "color": "#d8417f", "style": "dashed"}, {"source": "m_px4io", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_rc_input", "target": "t_input_rc", "color": "#d8417f", "style": "dashed"}, {"source": "m_rc_input", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_safety_button", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_safety_button", "target": "t_safety_button", "color": "#d841af", "style": "dashed"}, {"source": "m_safety_button", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_safety_button", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_outputs", "color": "#41d893", "style": "dashed"}, {"source": "m_uavcan", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_uavcan", "target": "t_safety_button", "color": "#d841af", "style": "dashed"}, {"source": "m_uavcan", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_esc_status", "color": "#d84147", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_armed", "color": "#7f41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_uavcan", "target": "t_actuator_motors", "color": "#ca41d8", "style": "dashed"}, {"source": "m_uavcan", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_uavcan", "target": "t_uavcan_parameter_value", "color": "#c4d841", "style": "dashed"}, {"source": "m_uavcan", "target": "t_open_drone_id_arm_status", "color": "#41d87f", "style": "dashed"}, {"source": "m_uavcan", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#41d841", "style": "dashed"}, {"source": "m_battery_status", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d8a141", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#d84171", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#71d841", "style": "dashed"}, {"source": "m_commander", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41cad8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#a841d8", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#4155d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d8a8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#7f41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#41d8af", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#416ad8", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#d88c41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d89a41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#ca41d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d87141", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d841c4", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d84e41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#41c4d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#4178d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#4163d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#d841d1", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#47d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d84193", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d8418c", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d8af41", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#41d8bd", "style": "dashed"}, {"source": "m_esc_battery", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_send_event", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#7841d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d8d841", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#af41d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#d141d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d863", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4147d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#419ad8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#41d85c", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#d841b6", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#4185d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#41d8a1", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#bd41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#c441d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#d8d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41d84e", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#4171d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#41afd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#41a8d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#d8414e", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d885", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#41afd8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d863", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#b6d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#afd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#5cd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#55d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#4141d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#93d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#8cd841", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#78d841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#a141d8", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#63d841", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#d86a41", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#d841a1", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#d8bd41", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d8d841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#41d8af", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84178", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#a141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d84741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d84141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#41d8d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41bdd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#d86341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#d8419a", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#a1d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41a1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#b641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#4193d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#7fd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#6ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d87841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_operator_id", "color": "#417fd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_self_id", "color": "#d88541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#4178d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#d841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#415cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d841ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#4ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#4155d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#4141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#4741d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#4e41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#41d863", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d8418c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#41d878", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d8af41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#5541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#d8417f", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#41d8ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#41d871", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#7141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#7841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#8541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d1d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#8c41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d8c4", "style": "dashed"}, {"source": "m_mavlink", "target": "t_uavcan_parameter_request", "color": "#9341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_open_drone_id_system", "color": "#bdd841", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#41d863", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#4147d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#d8416a", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#7141d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#7841d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#af41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4171d8", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#41d89a", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#41d863", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d1d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8c4", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#85d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#78d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d841a8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#4ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#d8a841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41d855", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d84185", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d8af41", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8b641", "style": "dashed"}, {"source": "m_navigator", "target": "t_distance_sensor_mode_change_request", "color": "#d8d141", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d8a8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#41d8af", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#41d8ca", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#9a41d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#d8bd41", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d85541", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#47d841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#d84163", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d87f41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#8541d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#9ad841", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41a1d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41b6d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d84155", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d88c", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#41d86a", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#7141d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#6341d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d85c41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d847", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#41afd8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#5c41d8", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#41d8b6", "style": "dashed"}, {"source": "m_led_control", "target": "t_led_control", "color": "#d841bd", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#418cd8", "style": "dashed"}, {"source": "t_adc_report", "target": "m_board_adc", "color": "#a8d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_capture", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d84155", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_cdcacm_autostart", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_lightware_laser_i2c", "color": "#41d8af", "style": "normal"}, {"source": "t_distance_sensor_mode_change_request", "target": "m_lightware_laser_i2c", "color": "#d8d141", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_dshot", "color": "#afd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_dshot", "color": "#d8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_dshot", "color": "#7f41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_dshot", "color": "#41d8b6", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_dshot", "color": "#ca41d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_dshot", "color": "#d141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_dshot", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_dshot", "color": "#41d8d1", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_dshot", "color": "#d87141", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_septentrio", "color": "#d84141", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d84141", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_heater", "color": "#41d871", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled", "color": "#d841bd", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_is31fl3195", "color": "#d841bd", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_lp5562", "color": "#d841bd", "style": "normal"}, {"source": "t_led_control", "target": "m_rgbled_ncp5623c", "color": "#d841bd", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#4178d8", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d8a8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d8af41", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d8417f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina226", "color": "#41d8af", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina226", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina228", "color": "#41d8af", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina228", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ina238", "color": "#41d8af", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_ina238", "color": "#41d85c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pm_selector_auterion", "color": "#7f41d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out", "color": "#afd841", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out", "color": "#d8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out", "color": "#7f41d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out", "color": "#41d8b6", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out", "color": "#ca41d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out", "color": "#d141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out", "color": "#41d8d1", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out", "color": "#d87141", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_px4io", "color": "#afd841", "style": "normal"}, {"source": "t_px4io_status", "target": "m_px4io", "color": "#414ed8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_px4io", "color": "#d8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_px4io", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_px4io", "color": "#41d8af", "style": "normal"}, {"source": "t_actuator_test", "target": "m_px4io", "color": "#41d8b6", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_px4io", "color": "#ca41d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_px4io", "color": "#d141d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_px4io", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_px4io", "color": "#41d8d1", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_px4io", "color": "#d87141", "style": "normal"}, {"source": "t_adc_report", "target": "m_rc_input", "color": "#a8d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_rc_input", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_rc_input", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_rc_input", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rc_input", "color": "#d8418c", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_safety_button", "color": "#7f41d8", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#418cd8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_uavcan", "color": "#d84141", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_uavcan", "color": "#afd841", "style": "normal"}, {"source": "t_tune_control", "target": "m_uavcan", "color": "#418cd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_uavcan", "color": "#78d841", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_uavcan", "color": "#d87141", "style": "normal"}, {"source": "t_open_drone_id_operator_id", "target": "m_uavcan", "color": "#417fd8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uavcan", "color": "#4178d8", "style": "normal"}, {"source": "t_open_drone_id_self_id", "target": "m_uavcan", "color": "#d88541", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_uavcan", "color": "#ca41d8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_uavcan", "color": "#d141d8", "style": "normal"}, {"source": "t_led_control", "target": "m_uavcan", "color": "#d841bd", "style": "normal"}, {"source": "t_landing_gear", "target": "m_uavcan", "color": "#d8d841", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_uavcan", "color": "#7f41d8", "style": "normal"}, {"source": "t_home_position", "target": "m_uavcan", "color": "#41d8a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_uavcan", "color": "#41d8af", "style": "normal"}, {"source": "t_actuator_test", "target": "m_uavcan", "color": "#41d8b6", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_uavcan", "color": "#d84155", "style": "normal"}, {"source": "t_uavcan_parameter_request", "target": "m_uavcan", "color": "#9341d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uavcan", "color": "#41d8d1", "style": "normal"}, {"source": "t_open_drone_id_system", "target": "m_uavcan", "color": "#bdd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#78d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d84e41", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d885", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#41d8af", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#41d8bd", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#419ad8", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_status", "color": "#41d8af", "style": "normal"}, {"source": "t_adc_report", "target": "m_battery_status", "color": "#a8d841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_status", "color": "#41d85c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d8418c", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d8af41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#4141d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d1d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d84e41", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#41c4d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41b6d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#d86341", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#9ad841", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#85d841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#78d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#6ad841", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#63d841", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#4178d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89341", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#ca41d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#d841d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#4163d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#d841d1", "style": "normal"}, {"source": "t_safety_button", "target": "m_commander", "color": "#d841af", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d841a8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#47d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#4155d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d847", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#d841a1", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d8418c", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#5541d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d8af41", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d84185", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#41d871", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84178", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d88c", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#d84171", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#d8bd41", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#d84163", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#7f41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#8541d8", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d8a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#41d8af", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#cad841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#41d8bd", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d84155", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#d8419a", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8d1", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41cad8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#41d86a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#a841d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#6341d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#d8bd41", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d85c41", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#5c41d8", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#41d8ca", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#78d841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d885", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d85541", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#6ad841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#47d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#41d841", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#d84163", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d87f41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#4741d8", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_esc_battery", "color": "#41d8af", "style": "normal"}, {"source": "t_esc_status", "target": "m_esc_battery", "color": "#d84147", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_esc_battery", "color": "#41d85c", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#63d841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#416ad8", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#78d841", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#a841d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#a841d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#bd41d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#4147d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d8418c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#41d8af", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#78d841", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#4185d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#a841d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#41c4d8", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d8a1", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#4178d8", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#41afd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#41d8af", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#41a8d8", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#a841d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#41c4d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#7841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#4178d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d8418c", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d8af41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#a841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#41d841", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#41d8af", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d89a41", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#41d863", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8b641", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41bdd8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#4141d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d84155", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#8c41d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d8418c", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#41d878", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d8af41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#41d8af", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#41d871", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41b6d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#d8419a", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d885", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#d8416a", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#a841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#47d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#7841d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#4178d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#7f41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#9ad841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d8af41", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d8418c", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#b641d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#4178d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#41d8af", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#4e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d84155", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#41d8af", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#a1d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#41d8af", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84178", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d84e41", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#d86341", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#d86a41", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d87841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d87f41", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#d88c41", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89341", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d8a141", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d8af41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#d8bd41", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8c441", "style": "normal"}, {"source": "t_uavcan_parameter_value", "target": "m_mavlink", "color": "#c4d841", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#b6d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#9ad841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#a1d841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#93d841", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#8cd841", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#7fd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#78d841", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#71d841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#63d841", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#5cd841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#55d841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#4ed841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#47d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#41d841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d847", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#41d863", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#41d878", "style": "normal"}, {"source": "t_open_drone_id_arm_status", "target": "m_mavlink", "color": "#41d87f", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#41d893", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d8a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#41d8af", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#41d8bd", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d8c4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8d1", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#41d8d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d1d8", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#41c4d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41b6d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#419ad8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41a1d8", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#4171d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#416ad8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#4163d8", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#4155d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#4147d8", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#4141d8", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#5c41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#7f41d8", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#8541d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#a141d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#a841d8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#c441d8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d841ca", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d841b6", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d841c4", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d841a8", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d84193", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d8418c", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d84185", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#d8417f", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d8415c", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d84155", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#a841d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#7141d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#4147d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d8418c", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#41d89a", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d86a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#a841d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#7841d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#af41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#a841d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89341", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#41d8af", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d89a41", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#41d863", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#78d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#a141d8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d841c4", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#4ed841", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#41c4d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#d8a841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#4178d8", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41d84e", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d8a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d84155", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8c4", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d8af41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#9a41d8", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#d8bd41", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d8417f", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#6a41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#a841d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#47d841", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d87f41", "style": "normal"}, {"source": "t_adc_report", "target": "m_sensors", "color": "#a8d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#8541d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41b6d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d1d841", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#9ad841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#a1d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#4163d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#d8419a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#41d871", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d87841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#a1d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d84155", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#d8419a", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#41d871", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d847", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#a841d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#78d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#4178d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#4171d8", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#415cd8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#41d841", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41d855", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d8418c", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84178", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d8ca41", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d8a8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#41d8af", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d84155", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_i2c_launcher", "color": "#41d8af", "style": "normal"}]} \ No newline at end of file diff --git a/docs/public/middleware/graph_px4_sitl.json b/docs/public/middleware/graph_px4_sitl.json index 04d7687057c5..eb6e1afc8c78 100644 --- a/docs/public/middleware/graph_px4_sitl.json +++ b/docs/public/middleware/graph_px4_sitl.json @@ -1 +1 @@ -{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_fake_magnetometer", "name": "fake_magnetometer", "type": "Module", "color": "#666666"}, {"id": "m_px4_mavlink_debug", "name": "px4_mavlink_debug", "type": "Module", "color": "#666666"}, {"id": "m_work_item_example", "name": "work_item_example", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_px4_simple_app", "name": "px4_simple_app", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_fake_imu", "name": "fake_imu", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#84d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#9e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#418dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#4173d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#a5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#a541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#41d88d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#8441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d873", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#9ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_actuator_test", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#d88241", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#cc41d8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#d89c41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8a941", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#9ed841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#98d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#91d841", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#41d879", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41d880", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#41a1d8", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#4193d8", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#b241d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#d841bd", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#d86841", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#d86e41", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#d8b041", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d8c441", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#b9d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#b2d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#abd841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#a5d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#7141d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#cc41d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#d84196", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#d8417b", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#d84147", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_esc_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro_fifo", "color": "#5d41d8", "style": "dashed"}, {"source": "m_fake_magnetometer", "target": "t_sensor_mag", "color": "#6341d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#41d893", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#d841c4", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#41d89a", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88941", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#6ad841", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#9141d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#8bd841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#84d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#7ed841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#77d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#41d893", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#41d8a7", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41d8ae", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8bb", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#41bbd8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#41b4d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#7e41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#d84189", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#7e41d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#50d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#49d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#41d845", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#41d84b", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#41d85f", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#41d866", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#41ced8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#41d86c", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#4152d8", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#d86841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#49d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#43d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#6341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#6a41d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#c641d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#d341d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#d8418f", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#d84154", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#d8419c", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#41d8a1", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d8b641", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#abd841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#d84196", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#d8417b", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8b4", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#b941d8", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d84141", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#41d893", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8c1", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#41d8c8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#d89641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d8a341", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8bd41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#d8d741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#d3d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#9ed841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#63d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#49d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#43d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#41d852", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#41d859", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#41d86c", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#41d886", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#41d88d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#41d8a1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d8ce", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#41d8d5", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#41c1d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#419ad8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#5d41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#6341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#6a41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#9841d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#bf41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#cc41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#d841d7", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#d84196", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84182", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84154", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d88941", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#8b41d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#a541d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d7", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#d841c4", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#d84189", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d84e41", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#d84175", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8bd41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#5dd841", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#56d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41d880", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#41d8d5", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#41d5d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#41c8d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#41a7d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#415fd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#4159d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#ab41d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d841b6", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#d8419c", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#d8416e", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#d84168", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d873", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#d84741", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#d85b41", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d86141", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#d86841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#d87541", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_array", "color": "#d8ca41", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_key_value", "color": "#d8d141", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_value", "color": "#d8d741", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_vect", "color": "#d3d841", "style": "dashed"}, {"source": "m_px4_simple_app", "target": "t_vehicle_attitude", "color": "#cc41d8", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#41d8c8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#d86841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#41aed8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#418dd8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#4186d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#4173d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#416cd8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#418dd8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#4186d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#4173d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#416cd8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#d85441", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#418dd8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#4186d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#4179d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#4173d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#416cd8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#41aed8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d7", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#b241d8", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#d88f41", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#5041d8", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#6341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#4341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#7141d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#7741d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a9", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#d841a3", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#ccd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#bfd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#41d886", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#41d88d", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#4166d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#4145d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#5d41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#6341d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#6a41d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#c641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#d341d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d841b0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#d8418f", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#d84182", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#d84154", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#d87b41", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#c6d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#414bd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#5641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#5d41d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#c641d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#d341d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d841b0", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#d8418f", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#8441d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#4941d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d8bd41", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#b241d8", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#b241d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d7", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d841d1", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#7e41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#9e41d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#d841d7", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#d841ca", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#d84161", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#d8415b", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#d8414e", "style": "dashed"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#d87b41", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#b9d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#abd841", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#6ad841", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41d8ae", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#d84161", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#d84154", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#d84168", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8a941", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#49d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#d84196", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d84141", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#d89641", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d8b641", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#ccd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#c6d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#bfd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#b9d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#b2d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#a5d841", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#9ed841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#5dd841", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41d880", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8b4", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8c1", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#41d8c8", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#41d5d8", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#41c8d8", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#41c1d8", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#41a1d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#4159d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#6341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#7141d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#7741d8", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#8441d8", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#9841d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#d84168", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#d8414e", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#91d841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#71d841", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#41d8c8", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#4166d8", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#7e41d8", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#d8415b", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8bd41", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#d88241", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#d88f41", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#c6d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#41d8a1", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41d8ae", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#4341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#7141d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#7741d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fake_magnetometer", "color": "#cc41d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#d88241", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#77d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#d88241", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#84d841", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#7ed841", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#71d841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8a7", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#d88241", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8c1", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#41a7d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#d84147", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#d89641", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#d8b041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#49d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#41d852", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#41d859", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8c1", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#d8416e", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#41d86c", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#5d41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#d841a3", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#d86e41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#d87541", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#50d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#41d845", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d873", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#41d893", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d841d1", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#d84741", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#d88241", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41d8ae", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#41a7d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#7141d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#8b41d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#d84161", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#41d88d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#d84196", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#d84741", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#c6d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#41d8a1", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#d84154", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#d89641", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8c1", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#d84168", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d84141", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#d88241", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d88941", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8a941", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d8b641", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d8c441", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#d8ca41", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d141", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#d8d741", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#d3d841", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#b9d841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#b2d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#9ed841", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#98d841", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#8bd841", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#5dd841", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#49d841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#41d85f", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#41d86c", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#41d879", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#41d886", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#41d8a1", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8c1", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#41d8c8", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#41d8d5", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#41ced8", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#41bbd8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#41a7d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#4159d8", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#4152d8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#6341d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#9141d8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#ab41d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#d84189", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#d84161", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d88941", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d84e41", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#d8415b", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#d841c4", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#d84196", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#d89641", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#d8b041", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#d88241", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#d89641", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41d880", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#41d886", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#d84168", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d8c441", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#56d841", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41d880", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#41d8a1", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#41d8d5", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#41b4d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#41aed8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#415fd8", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#ab41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#d84168", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d841d1", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#d84741", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#d86e41", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#d87541", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#50d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d873", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#41d893", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d841d1", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#41d886", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#41d8c8", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#419ad8", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#d85441", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#d86841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d8c1", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#41c1d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#41aed8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#41a7d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#418dd8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#4186d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#4179d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#4173d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#416cd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#d84196", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#d85441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d8c1", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#41c1d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#41a7d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#418dd8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#4186d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#4179d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#4173d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#416cd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#d84196", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#d85441", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d8c1", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#41c1d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#41a7d8", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#418dd8", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#4186d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#4179d8", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#4173d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#416cd8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#d84196", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d841b6", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#d84196", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#d89641", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d8b641", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#98d841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#d84168", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#d341d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d841b0", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#ccd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#b2d841", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#6341d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#6a41d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#d841a3", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#d84168", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#d85b41", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d86141", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#414bd8", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#4145d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#5641d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d841d1", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d8c441", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#41d886", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#b241d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d8c1", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#d841d7", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#d841ca", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d84141", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#d88241", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#63d841", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41d880", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#41a7d8", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d841d1", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#d84189", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#d84168", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_work_item_example", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_work_item_example", "color": "#d84168", "style": "normal"}]} \ No newline at end of file +{"nodes": [{"id": "m_fw_autotune_attitude_control", "name": "fw_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_autotune_attitude_control", "name": "mc_autotune_attitude_control", "type": "Module", "color": "#666666"}, {"id": "m_landing_target_estimator", "name": "landing_target_estimator", "type": "Module", "color": "#666666"}, {"id": "m_local_position_estimator", "name": "local_position_estimator", "type": "Module", "color": "#666666"}, {"id": "m_temperature_compensation", "name": "temperature_compensation", "type": "Module", "color": "#666666"}, {"id": "m_system_power_simulator", "name": "system_power_simulator", "type": "Module", "color": "#666666"}, {"id": "m_attitude_estimator_q", "name": "attitude_estimator_q", "type": "Module", "color": "#666666"}, {"id": "m_airship_att_control", "name": "airship_att_control", "type": "Module", "color": "#666666"}, {"id": "m_flight_mode_manager", "name": "flight_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_sensor_airspeed_sim", "name": "sensor_airspeed_sim", "type": "Module", "color": "#666666"}, {"id": "m_fw_lat_lon_control", "name": "fw_lat_lon_control", "type": "Module", "color": "#666666"}, {"id": "m_mag_bias_estimator", "name": "mag_bias_estimator", "type": "Module", "color": "#666666"}, {"id": "m_rover_differential", "name": "rover_differential", "type": "Module", "color": "#666666"}, {"id": "m_airspeed_selector", "name": "airspeed_selector", "type": "Module", "color": "#666666"}, {"id": "m_control_allocator", "name": "control_allocator", "type": "Module", "color": "#666666"}, {"id": "m_payload_deliverer", "name": "payload_deliverer", "type": "Module", "color": "#666666"}, {"id": "m_rover_pos_control", "name": "rover_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_battery_simulator", "name": "battery_simulator", "type": "Module", "color": "#666666"}, {"id": "m_simulator_mavlink", "name": "simulator_mavlink", "type": "Module", "color": "#666666"}, {"id": "m_fake_magnetometer", "name": "fake_magnetometer", "type": "Module", "color": "#666666"}, {"id": "m_px4_mavlink_debug", "name": "px4_mavlink_debug", "type": "Module", "color": "#666666"}, {"id": "m_work_item_example", "name": "work_item_example", "type": "Module", "color": "#666666"}, {"id": "m_gyro_calibration", "name": "gyro_calibration", "type": "Module", "color": "#666666"}, {"id": "m_uxrce_dds_client", "name": "uxrce_dds_client", "type": "Module", "color": "#666666"}, {"id": "m_vtol_att_control", "name": "vtol_att_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_feedback", "name": "camera_feedback", "type": "Module", "color": "#666666"}, {"id": "m_fw_mode_manager", "name": "fw_mode_manager", "type": "Module", "color": "#666666"}, {"id": "m_fw_rate_control", "name": "fw_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_rate_control", "name": "mc_rate_control", "type": "Module", "color": "#666666"}, {"id": "m_rover_ackermann", "name": "rover_ackermann", "type": "Module", "color": "#666666"}, {"id": "m_sensor_baro_sim", "name": "sensor_baro_sim", "type": "Module", "color": "#666666"}, {"id": "m_uuv_att_control", "name": "uuv_att_control", "type": "Module", "color": "#666666"}, {"id": "m_uuv_pos_control", "name": "uuv_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_camera_trigger", "name": "camera_trigger", "type": "Module", "color": "#666666"}, {"id": "m_fw_att_control", "name": "fw_att_control", "type": "Module", "color": "#666666"}, {"id": "m_manual_control", "name": "manual_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_att_control", "name": "mc_att_control", "type": "Module", "color": "#666666"}, {"id": "m_mc_pos_control", "name": "mc_pos_control", "type": "Module", "color": "#666666"}, {"id": "m_sensor_agp_sim", "name": "sensor_agp_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_gps_sim", "name": "sensor_gps_sim", "type": "Module", "color": "#666666"}, {"id": "m_sensor_mag_sim", "name": "sensor_mag_sim", "type": "Module", "color": "#666666"}, {"id": "m_px4_simple_app", "name": "px4_simple_app", "type": "Module", "color": "#666666"}, {"id": "m_land_detector", "name": "land_detector", "type": "Module", "color": "#666666"}, {"id": "m_rover_mecanum", "name": "rover_mecanum", "type": "Module", "color": "#666666"}, {"id": "m_simulator_sih", "name": "simulator_sih", "type": "Module", "color": "#666666"}, {"id": "m_actuator_test", "name": "actuator_test", "type": "Module", "color": "#666666"}, {"id": "m_tune_control", "name": "tune_control", "type": "Module", "color": "#666666"}, {"id": "m_pwm_out_sim", "name": "pwm_out_sim", "type": "Module", "color": "#666666"}, {"id": "m_tone_alarm", "name": "tone_alarm", "type": "Module", "color": "#666666"}, {"id": "m_send_event", "name": "send_event", "type": "Module", "color": "#666666"}, {"id": "m_commander", "name": "commander", "type": "Module", "color": "#666666"}, {"id": "m_navigator", "name": "navigator", "type": "Module", "color": "#666666"}, {"id": "m_rc_update", "name": "rc_update", "type": "Module", "color": "#666666"}, {"id": "m_gz_bridge", "name": "gz_bridge", "type": "Module", "color": "#666666"}, {"id": "m_gyro_fft", "name": "gyro_fft", "type": "Module", "color": "#666666"}, {"id": "m_load_mon", "name": "load_mon", "type": "Module", "color": "#666666"}, {"id": "m_fake_gps", "name": "fake_gps", "type": "Module", "color": "#666666"}, {"id": "m_fake_imu", "name": "fake_imu", "type": "Module", "color": "#666666"}, {"id": "m_msp_osd", "name": "msp_osd", "type": "Module", "color": "#666666"}, {"id": "m_dataman", "name": "dataman", "type": "Module", "color": "#666666"}, {"id": "m_mavlink", "name": "mavlink", "type": "Module", "color": "#666666"}, {"id": "m_sensors", "name": "sensors", "type": "Module", "color": "#666666"}, {"id": "m_failure", "name": "failure", "type": "Module", "color": "#666666"}, {"id": "m_gimbal", "name": "gimbal", "type": "Module", "color": "#666666"}, {"id": "m_logger", "name": "logger", "type": "Module", "color": "#666666"}, {"id": "m_tests", "name": "tests", "type": "Module", "color": "#666666"}, {"id": "m_ekf2", "name": "ekf2", "type": "Module", "color": "#666666"}, {"id": "m_gps", "name": "gps", "type": "Module", "color": "#666666"}, {"id": "t_vehicle_angular_velocity_groundtruth", "name": "vehicle_angular_velocity_groundtruth", "type": "topic", "color": "#41d852", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position_groundtruth", "name": "vehicle_global_position_groundtruth", "type": "topic", "color": "#d8419c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_groundtruth", "name": "vehicle_local_position_groundtruth", "type": "topic", "color": "#a5d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_landing_status", "name": "position_controller_landing_status", "type": "topic", "color": "#50d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_longitudinal_control_configuration", "name": "longitudinal_control_configuration", "type": "topic", "color": "#41d8bb", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_manual_control", "name": "gimbal_manager_set_manual_control", "type": "topic", "color": "#d841b6", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_autotune_attitude_control_status", "name": "autotune_attitude_control_status", "type": "topic", "color": "#d89c41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_longitudinal_setpoint", "name": "fixed_wing_longitudinal_setpoint", "type": "topic", "color": "#bf41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position_setpoint", "name": "vehicle_local_position_setpoint", "type": "topic", "color": "#4186d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_attitude_status", "name": "gimbal_device_attitude_status", "type": "topic", "color": "#d86141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_lateral_control_configuration", "name": "lateral_control_configuration", "type": "topic", "color": "#77d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mc_virtual_attitude_setpoint", "name": "mc_virtual_attitude_setpoint", "type": "topic", "color": "#41d886", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_groundtruth", "name": "vehicle_attitude_groundtruth", "type": "topic", "color": "#4173d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_register_ext_component_reply", "name": "register_ext_component_reply", "type": "topic", "color": "#d341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fw_virtual_attitude_setpoint", "name": "fw_virtual_attitude_setpoint", "type": "topic", "color": "#d84182", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_lateral_setpoint", "name": "fixed_wing_lateral_setpoint", "type": "topic", "color": "#41d893", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_set_attitude", "name": "gimbal_manager_set_attitude", "type": "topic", "color": "#ab41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_controls_status_0", "name": "actuator_controls_status_0", "type": "topic", "color": "#d8a941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorControlsStatus.msg"}, {"id": "t_gimbal_manager_information", "name": "gimbal_manager_information", "type": "topic", "color": "#c6d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_controller_status", "name": "position_controller_status", "type": "topic", "color": "#5dd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_set_attitude", "name": "gimbal_device_set_attitude", "type": "topic", "color": "#415fd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_fixed_wing_runway_control", "name": "fixed_wing_runway_control", "type": "topic", "color": "#4159d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_attitude_setpoint", "name": "vehicle_attitude_setpoint", "type": "topic", "color": "#5041d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_device_information", "name": "gimbal_device_information", "type": "topic", "color": "#d841ca", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_position_setpoint_triplet", "name": "position_setpoint_triplet", "type": "topic", "color": "#d84154", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_selector_status", "name": "estimator_selector_status", "type": "topic", "color": "#d84147", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tiltrotor_extra_controls", "name": "tiltrotor_extra_controls", "type": "topic", "color": "#d84741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_control_allocator_status", "name": "control_allocator_status", "type": "topic", "color": "#4179d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_steering_setpoint", "name": "rover_steering_setpoint", "type": "topic", "color": "#d86e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_global_position", "name": "vehicle_global_position", "type": "topic", "color": "#d87541", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_position_setpoint", "name": "rover_position_setpoint", "type": "topic", "color": "#d8c441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_throttle_setpoint", "name": "rover_throttle_setpoint", "type": "topic", "color": "#d3d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_switches", "name": "manual_control_switches", "type": "topic", "color": "#ccd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_velocity_setpoint", "name": "rover_velocity_setpoint", "type": "topic", "color": "#b9d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_thrust_setpoint", "name": "vehicle_thrust_setpoint", "type": "topic", "color": "#41d879", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleThrustSetpoint.msg"}, {"id": "t_failure_detector_status", "name": "failure_detector_status", "type": "topic", "color": "#41d8ae", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_manual_control_setpoint", "name": "manual_control_setpoint", "type": "topic", "color": "#41d8ce", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_launch_detection_status", "name": "launch_detection_status", "type": "topic", "color": "#41c8d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_visual_odometry", "name": "vehicle_visual_odometry", "type": "topic", "color": "#414bd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rover_attitude_setpoint", "name": "rover_attitude_setpoint", "type": "topic", "color": "#5d41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_torque_setpoint", "name": "vehicle_torque_setpoint", "type": "topic", "color": "#6341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/VehicleTorqueSetpoint.msg"}, {"id": "t_flight_phase_estimation", "name": "flight_phase_estimation", "type": "topic", "color": "#8b41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_rates_setpoint", "name": "vehicle_rates_setpoint", "type": "topic", "color": "#71d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status_flags", "name": "estimator_status_flags", "type": "topic", "color": "#41d8a1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_local_position", "name": "vehicle_local_position", "type": "topic", "color": "#b941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_mocap_odometry", "name": "vehicle_mocap_odometry", "type": "topic", "color": "#c641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_land_detected", "name": "vehicle_land_detected", "type": "topic", "color": "#7ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_sensor_bias", "name": "estimator_sensor_bias", "type": "topic", "color": "#41d866", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_manager_status", "name": "gimbal_manager_status", "type": "topic", "color": "#4193d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_offboard_control_mode", "name": "offboard_control_mode", "type": "topic", "color": "#4152d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_differential_pressure", "name": "differential_pressure", "type": "topic", "color": "#d841d1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_control_mode", "name": "vehicle_control_mode", "type": "topic", "color": "#41d84b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos_trim", "name": "actuator_servos_trim", "type": "topic", "color": "#41c1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs_sim", "name": "actuator_outputs_sim", "type": "topic", "color": "#d841bd", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_rover_rate_setpoint", "name": "rover_rate_setpoint", "type": "topic", "color": "#d84e41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_figure_eight_status", "name": "figure_eight_status", "type": "topic", "color": "#d85b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_optical_flow", "name": "sensor_optical_flow", "type": "topic", "color": "#d8ca41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_target_pose", "name": "landing_target_pose", "type": "topic", "color": "#6ad841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command_ack", "name": "vehicle_command_ack", "type": "topic", "color": "#41d845", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vtol_vehicle_status", "name": "vtol_vehicle_status", "type": "topic", "color": "#41d859", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_constraints", "name": "vehicle_constraints", "type": "topic", "color": "#41d873", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_aux_global_position", "name": "aux_global_position", "type": "topic", "color": "#cc41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource2d.msg"}, {"id": "t_trajectory_setpoint", "name": "trajectory_setpoint", "type": "topic", "color": "#d8416e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_power_button_state", "name": "power_button_state", "type": "topic", "color": "#98d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_transponder_report", "name": "transponder_report", "type": "topic", "color": "#91d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu_status", "name": "vehicle_imu_status", "type": "topic", "color": "#41d5d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensors_status_imu", "name": "sensors_status_imu", "type": "topic", "color": "#419ad8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed_validated", "name": "airspeed_validated", "type": "topic", "color": "#4166d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear_wheel", "name": "landing_gear_wheel", "type": "topic", "color": "#6a41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_v1_command", "name": "gimbal_v1_command", "type": "topic", "color": "#bfd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_correction", "name": "sensor_correction", "type": "topic", "color": "#41a7d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mount_orientation", "name": "mount_orientation", "type": "topic", "color": "#9841d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_spoilers_setpoint", "name": "spoilers_setpoint", "type": "topic", "color": "#d841c4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_rtl_time_estimate", "name": "rtl_time_estimate", "type": "topic", "color": "#d8417b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_response", "name": "dataman_response", "type": "topic", "color": "#d84141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_telemetry_status", "name": "telemetry_status", "type": "topic", "color": "#d85441", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_estimator_status", "name": "estimator_status", "type": "topic", "color": "#d86841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro_fifo", "name": "sensor_gyro_fifo", "type": "topic", "color": "#d88241", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_odometry", "name": "vehicle_odometry", "type": "topic", "color": "#9ed841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_navigator_status", "name": "navigator_status", "type": "topic", "color": "#49d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_selection", "name": "sensor_selection", "type": "topic", "color": "#41d880", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rc_parameter_map", "name": "rc_parameter_map", "type": "topic", "color": "#416cd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_outputs", "name": "actuator_outputs", "type": "topic", "color": "#a541d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ActuatorOutputs.msg"}, {"id": "t_vehicle_attitude", "name": "vehicle_attitude", "type": "topic", "color": "#d84175", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gps_inject_data", "name": "gps_inject_data", "type": "topic", "color": "#d87b41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_command", "name": "vehicle_command", "type": "topic", "color": "#d8bd41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_key_value", "name": "debug_key_value", "type": "topic", "color": "#d8d141", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_result", "name": "geofence_result", "type": "topic", "color": "#41d85f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_servos", "name": "actuator_servos", "type": "topic", "color": "#41d86c", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_distance_sensor", "name": "distance_sensor", "type": "topic", "color": "#41d88d", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_geofence_status", "name": "geofence_status", "type": "topic", "color": "#41d8b4", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gimbal_controls", "name": "gimbal_controls", "type": "topic", "color": "#41b4d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_motors", "name": "actuator_motors", "type": "topic", "color": "#4180d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream_ack", "name": "ulog_stream_ack", "type": "topic", "color": "#b241d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_combined", "name": "sensor_combined", "type": "topic", "color": "#d84196", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_dataman_request", "name": "dataman_request", "type": "topic", "color": "#d8414e", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_satellite_info", "name": "satellite_info", "type": "topic", "color": "#d8a341", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_takeoff_status", "name": "takeoff_status", "type": "topic", "color": "#b2d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_capture", "name": "camera_capture", "type": "topic", "color": "#63d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_status", "name": "vehicle_status", "type": "topic", "color": "#41ced8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_battery_status", "name": "battery_status", "type": "topic", "color": "#7141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_failsafe_flags", "name": "failsafe_flags", "type": "topic", "color": "#7e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_armed", "name": "actuator_armed", "type": "topic", "color": "#8441d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_mission_result", "name": "mission_result", "type": "topic", "color": "#d841d7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_action_request", "name": "action_request", "type": "topic", "color": "#d8418f", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_flaps_setpoint", "name": "flaps_setpoint", "type": "topic", "color": "#d84168", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/NormalizedUnsignedSetpoint.msg"}, {"id": "t_camera_trigger", "name": "camera_trigger", "type": "topic", "color": "#d8415b", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_actuator_test", "name": "actuator_test", "type": "topic", "color": "#84d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_health_report", "name": "health_report", "type": "topic", "color": "#56d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_logger_status", "name": "logger_status", "type": "topic", "color": "#41d8d5", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_home_position", "name": "home_position", "type": "topic", "color": "#41a1d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_irlock_report", "name": "irlock_report", "type": "topic", "color": "#5641d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_camera_status", "name": "camera_status", "type": "topic", "color": "#d84189", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_accel", "name": "sensor_accel", "type": "topic", "color": "#d88941", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_orbit_status", "name": "orbit_status", "type": "topic", "color": "#d89641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tune_control", "name": "tune_control", "type": "topic", "color": "#d8b641", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_system_power", "name": "system_power", "type": "topic", "color": "#4145d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_landing_gear", "name": "landing_gear", "type": "topic", "color": "#d84161", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_array", "name": "debug_array", "type": "topic", "color": "#41d8c1", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_tecs_status", "name": "tecs_status", "type": "topic", "color": "#41d8c8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_roi", "name": "vehicle_roi", "type": "topic", "color": "#418dd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_value", "name": "debug_value", "type": "topic", "color": "#4341d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gyro", "name": "sensor_gyro", "type": "topic", "color": "#4941d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_ulog_stream", "name": "ulog_stream", "type": "topic", "color": "#7741d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_baro", "name": "sensor_baro", "type": "topic", "color": "#d841b0", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_vehicle_imu", "name": "vehicle_imu", "type": "topic", "color": "#d841a9", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_mag", "name": "sensor_mag", "type": "topic", "color": "#abd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_sensor_gps", "name": "sensor_gps", "type": "topic", "color": "#8bd841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/SensorGps.msg"}, {"id": "t_esc_status", "name": "esc_status", "type": "topic", "color": "#41d8a7", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_debug_vect", "name": "debug_vect", "type": "topic", "color": "#41aed8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_rtl_status", "name": "rtl_status", "type": "topic", "color": "#9e41d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_input_rc", "name": "input_rc", "type": "topic", "color": "#d8d741", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_airspeed", "name": "airspeed", "type": "topic", "color": "#41bbd8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/EstimatorAidSource1d.msg"}, {"id": "t_mission", "name": "mission", "type": "topic", "color": "#d88f41", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_gripper", "name": "gripper", "type": "topic", "color": "#41d89a", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_cpuload", "name": "cpuload", "type": "topic", "color": "#d841a3", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}, {"id": "t_event", "name": "event", "type": "topic", "color": "#d8b041", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/ButtonEvent.msg"}, {"id": "t_wind", "name": "wind", "type": "topic", "color": "#43d841", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/Wind.msg"}, {"id": "t_rpm", "name": "rpm", "type": "topic", "color": "#9141d8", "url": "https://github.com/PX4/PX4-Autopilot/blob/main/msg/no_file.msg"}], "links": [{"source": "m_camera_trigger", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_camera_trigger", "target": "t_camera_trigger", "color": "#d8415b", "style": "dashed"}, {"source": "m_gps", "target": "t_sensor_gps", "color": "#8bd841", "style": "dashed"}, {"source": "m_gps", "target": "t_gps_inject_data", "color": "#d87b41", "style": "dashed"}, {"source": "m_gps", "target": "t_satellite_info", "color": "#d8a341", "style": "dashed"}, {"source": "m_tone_alarm", "target": "t_tune_control", "color": "#d8b641", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_airship_att_control", "target": "t_vehicle_torque_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_airspeed_selector", "target": "t_airspeed_validated", "color": "#4166d8", "style": "dashed"}, {"source": "m_attitude_estimator_q", "target": "t_vehicle_attitude", "color": "#d84175", "style": "dashed"}, {"source": "m_camera_feedback", "target": "t_camera_capture", "color": "#63d841", "style": "dashed"}, {"source": "m_commander", "target": "t_register_ext_component_reply", "color": "#d341d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_test", "color": "#84d841", "style": "dashed"}, {"source": "m_commander", "target": "t_event", "color": "#d8b041", "style": "dashed"}, {"source": "m_commander", "target": "t_health_report", "color": "#56d841", "style": "dashed"}, {"source": "m_commander", "target": "t_failsafe_flags", "color": "#7e41d8", "style": "dashed"}, {"source": "m_commander", "target": "t_actuator_armed", "color": "#8441d8", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_control_mode", "color": "#41d84b", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_status", "color": "#41ced8", "style": "dashed"}, {"source": "m_commander", "target": "t_power_button_state", "color": "#98d841", "style": "dashed"}, {"source": "m_commander", "target": "t_tune_control", "color": "#d8b641", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_commander", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_commander", "target": "t_failure_detector_status", "color": "#41d8ae", "style": "dashed"}, {"source": "m_commander", "target": "t_home_position", "color": "#41a1d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos_trim", "color": "#41c1d8", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_actuator_servos", "color": "#41d86c", "style": "dashed"}, {"source": "m_control_allocator", "target": "t_control_allocator_status", "color": "#4179d8", "style": "dashed"}, {"source": "m_dataman", "target": "t_dataman_response", "color": "#d84141", "style": "dashed"}, {"source": "m_ekf2", "target": "t_wind", "color": "#43d841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_local_position", "color": "#b941d8", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status", "color": "#d86841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_global_position", "color": "#d87541", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_sensor_bias", "color": "#41d866", "style": "dashed"}, {"source": "m_ekf2", "target": "t_sensor_selection", "color": "#41d880", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_status_flags", "color": "#41d8a1", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_odometry", "color": "#9ed841", "style": "dashed"}, {"source": "m_ekf2", "target": "t_vehicle_attitude", "color": "#d84175", "style": "dashed"}, {"source": "m_ekf2", "target": "t_estimator_selector_status", "color": "#d84147", "style": "dashed"}, {"source": "m_send_event", "target": "t_tune_control", "color": "#d8b641", "style": "dashed"}, {"source": "m_send_event", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_vehicle_constraints", "color": "#41d873", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_landing_gear", "color": "#d84161", "style": "dashed"}, {"source": "m_flight_mode_manager", "target": "t_trajectory_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_landing_gear_wheel", "color": "#6a41d8", "style": "dashed"}, {"source": "m_fw_att_control", "target": "t_vehicle_rates_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_fw_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_flight_phase_estimation", "color": "#8b41d8", "style": "dashed"}, {"source": "m_fw_lat_lon_control", "target": "t_tecs_status", "color": "#41d8c8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_longitudinal_control_configuration", "color": "#41d8bb", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_lateral_control_configuration", "color": "#77d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_lateral_setpoint", "color": "#41d893", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_spoilers_setpoint", "color": "#d841c4", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_position_controller_landing_status", "color": "#50d841", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_vehicle_local_position_setpoint", "color": "#4186d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_flaps_setpoint", "color": "#d84168", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_orbit_status", "color": "#d89641", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_landing_gear", "color": "#d84161", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_figure_eight_status", "color": "#d85b41", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_launch_detection_status", "color": "#41c8d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_longitudinal_setpoint", "color": "#bf41d8", "style": "dashed"}, {"source": "m_fw_mode_manager", "target": "t_fixed_wing_runway_control", "color": "#4159d8", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_flaps_setpoint", "color": "#d84168", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_spoilers_setpoint", "color": "#d841c4", "style": "dashed"}, {"source": "m_fw_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_information", "color": "#c6d841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_v1_command", "color": "#bfd841", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_manager_status", "color": "#4193d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_set_attitude", "color": "#415fd8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_mount_orientation", "color": "#9841d8", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_device_attitude_status", "color": "#d86141", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_gimbal", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_gimbal", "target": "t_gimbal_controls", "color": "#41b4d8", "style": "dashed"}, {"source": "m_land_detector", "target": "t_vehicle_land_detected", "color": "#7ed841", "style": "dashed"}, {"source": "m_landing_target_estimator", "target": "t_landing_target_pose", "color": "#6ad841", "style": "dashed"}, {"source": "m_load_mon", "target": "t_cpuload", "color": "#d841a3", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_global_position", "color": "#d87541", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_odometry", "color": "#9ed841", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_vehicle_local_position", "color": "#b941d8", "style": "dashed"}, {"source": "m_local_position_estimator", "target": "t_estimator_status", "color": "#d86841", "style": "dashed"}, {"source": "m_logger", "target": "t_logger_status", "color": "#41d8d5", "style": "dashed"}, {"source": "m_logger", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_logger", "target": "t_ulog_stream", "color": "#7741d8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_switches", "color": "#ccd841", "style": "dashed"}, {"source": "m_manual_control", "target": "t_manual_control_setpoint", "color": "#41d8ce", "style": "dashed"}, {"source": "m_manual_control", "target": "t_landing_gear", "color": "#d84161", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_status", "color": "#41ced8", "style": "dashed"}, {"source": "m_manual_control", "target": "t_action_request", "color": "#d8418f", "style": "dashed"}, {"source": "m_manual_control", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_vect", "color": "#41aed8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_attitude", "color": "#ab41d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_ulog_stream_ack", "color": "#b241d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_telemetry_status", "color": "#d85441", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_local_position", "color": "#b941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_attitude_status", "color": "#d86141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_global_position", "color": "#d87541", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gps_inject_data", "color": "#d87b41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_differential_pressure", "color": "#d841d1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_device_information", "color": "#d841ca", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d88241", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_accel", "color": "#d88941", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mission", "color": "#d88f41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_rc_parameter_map", "color": "#416cd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_gimbal_manager_set_manual_control", "color": "#d841b6", "style": "dashed"}, {"source": "m_mavlink", "target": "t_event", "color": "#d8b041", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_baro", "color": "#d841b0", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_optical_flow", "color": "#d8ca41", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_key_value", "color": "#d8d141", "style": "dashed"}, {"source": "m_mavlink", "target": "t_tune_control", "color": "#d8b641", "style": "dashed"}, {"source": "m_mavlink", "target": "t_input_rc", "color": "#d8d741", "style": "dashed"}, {"source": "m_mavlink", "target": "t_mc_virtual_attitude_setpoint", "color": "#41d886", "style": "dashed"}, {"source": "m_mavlink", "target": "t_offboard_control_mode", "color": "#4152d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_visual_odometry", "color": "#414bd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_distance_sensor", "color": "#41d88d", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_value", "color": "#4341d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_irlock_report", "color": "#5641d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_mag", "color": "#abd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gyro", "color": "#4941d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_fw_virtual_attitude_setpoint", "color": "#d84182", "style": "dashed"}, {"source": "m_mavlink", "target": "t_camera_status", "color": "#d84189", "style": "dashed"}, {"source": "m_mavlink", "target": "t_battery_status", "color": "#7141d8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_transponder_report", "color": "#91d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_sensor_gps", "color": "#8bd841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_rates_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_debug_array", "color": "#41d8c1", "style": "dashed"}, {"source": "m_mavlink", "target": "t_vehicle_attitude", "color": "#d84175", "style": "dashed"}, {"source": "m_mavlink", "target": "t_trajectory_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_mavlink", "target": "t_landing_target_pose", "color": "#6ad841", "style": "dashed"}, {"source": "m_mavlink", "target": "t_airspeed", "color": "#41bbd8", "style": "dashed"}, {"source": "m_mavlink", "target": "t_dataman_request", "color": "#d8414e", "style": "dashed"}, {"source": "m_mc_att_control", "target": "t_vehicle_rates_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_mc_autotune_attitude_control", "target": "t_autotune_attitude_control_status", "color": "#d89c41", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_trajectory_setpoint", "color": "#d8416e", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_local_position_setpoint", "color": "#4186d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_takeoff_status", "color": "#b2d841", "style": "dashed"}, {"source": "m_mc_pos_control", "target": "t_vehicle_constraints", "color": "#41d873", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_vehicle_rates_setpoint", "color": "#71d841", "style": "dashed"}, {"source": "m_mc_rate_control", "target": "t_actuator_controls_status_0", "color": "#d8a941", "style": "dashed"}, {"source": "m_navigator", "target": "t_navigator_status", "color": "#49d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_navigator", "target": "t_home_position", "color": "#41a1d8", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_global_position", "color": "#d87541", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission_result", "color": "#d841d7", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_roi", "color": "#418dd8", "style": "dashed"}, {"source": "m_navigator", "target": "t_mission", "color": "#d88f41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_result", "color": "#41d85f", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_navigator", "target": "t_geofence_status", "color": "#41d8b4", "style": "dashed"}, {"source": "m_navigator", "target": "t_transponder_report", "color": "#91d841", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_time_estimate", "color": "#d8417b", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_land_detected", "color": "#7ed841", "style": "dashed"}, {"source": "m_navigator", "target": "t_vehicle_status", "color": "#41ced8", "style": "dashed"}, {"source": "m_navigator", "target": "t_position_setpoint_triplet", "color": "#d84154", "style": "dashed"}, {"source": "m_navigator", "target": "t_dataman_request", "color": "#d8414e", "style": "dashed"}, {"source": "m_navigator", "target": "t_rtl_status", "color": "#9e41d8", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_gripper", "color": "#41d89a", "style": "dashed"}, {"source": "m_payload_deliverer", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_rc_update", "target": "t_manual_control_switches", "color": "#ccd841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_position_controller_status", "color": "#5dd841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_velocity_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_rate_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_attitude_setpoint", "color": "#5d41d8", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_actuator_servos", "color": "#41d86c", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_position_setpoint", "color": "#d8c441", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_steering_setpoint", "color": "#d86e41", "style": "dashed"}, {"source": "m_rover_ackermann", "target": "t_rover_throttle_setpoint", "color": "#d3d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_velocity_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_rate_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_attitude_setpoint", "color": "#5d41d8", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_position_setpoint", "color": "#d8c441", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_steering_setpoint", "color": "#d86e41", "style": "dashed"}, {"source": "m_rover_differential", "target": "t_rover_throttle_setpoint", "color": "#d3d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_velocity_setpoint", "color": "#b9d841", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_rate_setpoint", "color": "#d84e41", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_attitude_setpoint", "color": "#5d41d8", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_position_setpoint", "color": "#d8c441", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_steering_setpoint", "color": "#d86e41", "style": "dashed"}, {"source": "m_rover_mecanum", "target": "t_rover_throttle_setpoint", "color": "#d3d841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_position_controller_status", "color": "#5dd841", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_rover_pos_control", "target": "t_vehicle_torque_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu", "color": "#d841a9", "style": "dashed"}, {"source": "m_sensors", "target": "t_differential_pressure", "color": "#d841d1", "style": "dashed"}, {"source": "m_sensors", "target": "t_vehicle_imu_status", "color": "#41d5d8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_combined", "color": "#d84196", "style": "dashed"}, {"source": "m_sensors", "target": "t_airspeed", "color": "#41bbd8", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensor_selection", "color": "#41d880", "style": "dashed"}, {"source": "m_sensors", "target": "t_sensors_status_imu", "color": "#419ad8", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_battery_simulator", "target": "t_battery_status", "color": "#7141d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_outputs", "color": "#a541d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_attitude_status", "color": "#d86141", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d852", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_differential_pressure", "color": "#d841d1", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_gimbal_device_information", "color": "#d841ca", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_accel", "color": "#d88941", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_attitude_groundtruth", "color": "#4173d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_servos", "color": "#41d86c", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_baro", "color": "#d841b0", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_optical_flow", "color": "#d8ca41", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_visual_odometry", "color": "#414bd8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_distance_sensor", "color": "#41d88d", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_global_position_groundtruth", "color": "#d8419c", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gyro", "color": "#4941d8", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_vehicle_local_position_groundtruth", "color": "#a5d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_mag", "color": "#abd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_esc_status", "color": "#41d8a7", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_sensor_gps", "color": "#8bd841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_test", "color": "#84d841", "style": "dashed"}, {"source": "m_gz_bridge", "target": "t_actuator_armed", "color": "#8441d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_test", "color": "#84d841", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs", "color": "#a541d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_outputs_sim", "color": "#d841bd", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_motors", "color": "#4180d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_armed", "color": "#8441d8", "style": "dashed"}, {"source": "m_pwm_out_sim", "target": "t_actuator_servos", "color": "#41d86c", "style": "dashed"}, {"source": "m_sensor_agp_sim", "target": "t_aux_global_position", "color": "#cc41d8", "style": "dashed"}, {"source": "m_sensor_airspeed_sim", "target": "t_differential_pressure", "color": "#d841d1", "style": "dashed"}, {"source": "m_sensor_baro_sim", "target": "t_sensor_baro", "color": "#d841b0", "style": "dashed"}, {"source": "m_sensor_gps_sim", "target": "t_sensor_gps", "color": "#8bd841", "style": "dashed"}, {"source": "m_sensor_mag_sim", "target": "t_sensor_mag", "color": "#abd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_mocap_odometry", "color": "#c641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d852", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro_fifo", "color": "#d88241", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_differential_pressure", "color": "#d841d1", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_accel", "color": "#d88941", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_attitude_groundtruth", "color": "#4173d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_baro", "color": "#d841b0", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_optical_flow", "color": "#d8ca41", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_input_rc", "color": "#d8d741", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_visual_odometry", "color": "#414bd8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_global_position_groundtruth", "color": "#d8419c", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_gyro", "color": "#4941d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_irlock_report", "color": "#5641d8", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_vehicle_local_position_groundtruth", "color": "#a5d841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_sensor_mag", "color": "#abd841", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_esc_status", "color": "#41d8a7", "style": "dashed"}, {"source": "m_simulator_mavlink", "target": "t_rpm", "color": "#9141d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_distance_sensor", "color": "#41d88d", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro_fifo", "color": "#d88241", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_global_position_groundtruth", "color": "#d8419c", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_accel", "color": "#d88941", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_attitude_groundtruth", "color": "#4173d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_sensor_gyro", "color": "#4941d8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_local_position_groundtruth", "color": "#a5d841", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_airspeed", "color": "#41bbd8", "style": "dashed"}, {"source": "m_simulator_sih", "target": "t_vehicle_angular_velocity_groundtruth", "color": "#41d852", "style": "dashed"}, {"source": "m_system_power_simulator", "target": "t_system_power", "color": "#4145d8", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_temperature_compensation", "target": "t_sensor_correction", "color": "#41a7d8", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_uuv_att_control", "target": "t_vehicle_torque_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_uuv_pos_control", "target": "t_vehicle_attitude_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_uxrce_dds_client", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_tiltrotor_extra_controls", "color": "#d84741", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vtol_vehicle_status", "color": "#41d859", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_spoilers_setpoint", "color": "#d841c4", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_attitude_setpoint", "color": "#5041d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_flaps_setpoint", "color": "#d84168", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_command_ack", "color": "#41d845", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_torque_setpoint", "color": "#6341d8", "style": "dashed"}, {"source": "m_vtol_att_control", "target": "t_vehicle_thrust_setpoint", "color": "#41d879", "style": "dashed"}, {"source": "m_actuator_test", "target": "t_actuator_test", "color": "#84d841", "style": "dashed"}, {"source": "m_failure", "target": "t_vehicle_command", "color": "#d8bd41", "style": "dashed"}, {"source": "m_tests", "target": "t_dataman_request", "color": "#d8414e", "style": "dashed"}, {"source": "m_tune_control", "target": "t_tune_control", "color": "#d8b641", "style": "dashed"}, {"source": "m_fake_gps", "target": "t_sensor_gps", "color": "#8bd841", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro_fifo", "color": "#d88241", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_accel", "color": "#d88941", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_sensor_gyro", "color": "#4941d8", "style": "dashed"}, {"source": "m_fake_imu", "target": "t_esc_status", "color": "#41d8a7", "style": "dashed"}, {"source": "m_fake_magnetometer", "target": "t_sensor_mag", "color": "#abd841", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_vect", "color": "#41aed8", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_array", "color": "#41d8c1", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_key_value", "color": "#d8d141", "style": "dashed"}, {"source": "m_px4_mavlink_debug", "target": "t_debug_value", "color": "#4341d8", "style": "dashed"}, {"source": "m_px4_simple_app", "target": "t_vehicle_attitude", "color": "#d84175", "style": "dashed"}, {"source": "t_vehicle_command", "target": "m_camera_trigger", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_camera_trigger", "color": "#b941d8", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_gps", "color": "#d87b41", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_msp_osd", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_msp_osd", "color": "#d84175", "style": "normal"}, {"source": "t_home_position", "target": "m_msp_osd", "color": "#41a1d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_msp_osd", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_msp_osd", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_msp_osd", "color": "#b941d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_msp_osd", "color": "#7141d8", "style": "normal"}, {"source": "t_input_rc", "target": "m_msp_osd", "color": "#d8d741", "style": "normal"}, {"source": "t_tune_control", "target": "m_tone_alarm", "color": "#d8b641", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airship_att_control", "color": "#41ced8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_airship_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_airspeed_selector", "color": "#7ed841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_airspeed_selector", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_airspeed_selector", "color": "#d84175", "style": "normal"}, {"source": "t_airspeed", "target": "m_airspeed_selector", "color": "#41bbd8", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_airspeed_selector", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_airspeed_selector", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_airspeed_selector", "color": "#b941d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_airspeed_selector", "color": "#41c8d8", "style": "normal"}, {"source": "t_estimator_status", "target": "m_airspeed_selector", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_airspeed_selector", "color": "#41d879", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_airspeed_selector", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_attitude_estimator_q", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_attitude_estimator_q", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_attitude_estimator_q", "color": "#b941d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_attitude_estimator_q", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_attitude_estimator_q", "color": "#c641d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_camera_feedback", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_camera_feedback", "color": "#d84175", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_camera_feedback", "color": "#d8415b", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_camera_feedback", "color": "#d86141", "style": "normal"}, {"source": "t_navigator_status", "target": "m_commander", "color": "#49d841", "style": "normal"}, {"source": "t_telemetry_status", "target": "m_commander", "color": "#d85441", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_commander", "color": "#b941d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_commander", "color": "#41a7d8", "style": "normal"}, {"source": "t_wind", "target": "m_commander", "color": "#43d841", "style": "normal"}, {"source": "t_estimator_status", "target": "m_commander", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_commander", "color": "#41d845", "style": "normal"}, {"source": "t_home_position", "target": "m_commander", "color": "#41a1d8", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_commander", "color": "#419ad8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_commander", "color": "#d87541", "style": "normal"}, {"source": "t_vtol_vehicle_status", "target": "m_commander", "color": "#41d859", "style": "normal"}, {"source": "t_mission_result", "target": "m_commander", "color": "#d841d7", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_commander", "color": "#d841d1", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_commander", "color": "#d88941", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_commander", "color": "#4180d8", "style": "normal"}, {"source": "t_geofence_result", "target": "m_commander", "color": "#41d85f", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_commander", "color": "#4166d8", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_commander", "color": "#41d866", "style": "normal"}, {"source": "t_event", "target": "m_commander", "color": "#d8b041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_commander", "color": "#d8bd41", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_commander", "color": "#d841b0", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_commander", "color": "#41d880", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_commander", "color": "#4152d8", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_commander", "color": "#41d88d", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_commander", "color": "#ccd841", "style": "normal"}, {"source": "t_cpuload", "target": "m_commander", "color": "#d841a3", "style": "normal"}, {"source": "t_system_power", "target": "m_commander", "color": "#4145d8", "style": "normal"}, {"source": "t_estimator_status_flags", "target": "m_commander", "color": "#41d8a1", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_commander", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_commander", "color": "#abd841", "style": "normal"}, {"source": "t_action_request", "target": "m_commander", "color": "#d8418f", "style": "normal"}, {"source": "t_power_button_state", "target": "m_commander", "color": "#98d841", "style": "normal"}, {"source": "t_esc_status", "target": "m_commander", "color": "#41d8a7", "style": "normal"}, {"source": "t_battery_status", "target": "m_commander", "color": "#7141d8", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_commander", "color": "#8bd841", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_commander", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_commander", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_commander", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_commander", "color": "#d84175", "style": "normal"}, {"source": "t_logger_status", "target": "m_commander", "color": "#41d8d5", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_commander", "color": "#41d5d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_commander", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_commander", "color": "#41ced8", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_commander", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_control_allocator", "color": "#41d879", "style": "normal"}, {"source": "t_tiltrotor_extra_controls", "target": "m_control_allocator", "color": "#d84741", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_control_allocator", "color": "#ccd841", "style": "normal"}, {"source": "t_spoilers_setpoint", "target": "m_control_allocator", "color": "#d841c4", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_control_allocator", "color": "#d84168", "style": "normal"}, {"source": "t_rpm", "target": "m_control_allocator", "color": "#9141d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_control_allocator", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_control_allocator", "color": "#6341d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_control_allocator", "color": "#41d84b", "style": "normal"}, {"source": "t_failure_detector_status", "target": "m_control_allocator", "color": "#41d8ae", "style": "normal"}, {"source": "t_dataman_request", "target": "m_dataman", "color": "#d8414e", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_ekf2", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_ekf2", "color": "#d841a9", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_ekf2", "color": "#7ed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_ekf2", "color": "#41d88d", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_ekf2", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_ekf2", "color": "#41ced8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_ekf2", "color": "#41c8d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_ekf2", "color": "#d84196", "style": "normal"}, {"source": "t_aux_global_position", "target": "m_ekf2", "color": "#cc41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_ekf2", "color": "#d8bd41", "style": "normal"}, {"source": "t_airspeed", "target": "m_ekf2", "color": "#41bbd8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_ekf2", "color": "#6ad841", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_ekf2", "color": "#41d880", "style": "normal"}, {"source": "t_sensors_status_imu", "target": "m_ekf2", "color": "#419ad8", "style": "normal"}, {"source": "t_cpuload", "target": "m_send_event", "color": "#d841a3", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_send_event", "color": "#7e41d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_send_event", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_send_event", "color": "#d8bd41", "style": "normal"}, {"source": "t_battery_status", "target": "m_send_event", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_flight_mode_manager", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_flight_mode_manager", "color": "#5041d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_flight_mode_manager", "color": "#b2d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_flight_mode_manager", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_flight_mode_manager", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_flight_mode_manager", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_flight_mode_manager", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_att_control", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_fw_att_control", "color": "#5041d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_fw_att_control", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_att_control", "color": "#41ced8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_att_control", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_att_control", "color": "#b941d8", "style": "normal"}, {"source": "t_fixed_wing_runway_control", "target": "m_fw_att_control", "color": "#4159d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_autotune_attitude_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_autotune_attitude_control", "color": "#41ced8", "style": "normal"}, {"source": "t_longitudinal_control_configuration", "target": "m_fw_lat_lon_control", "color": "#41d8bb", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_lat_lon_control", "color": "#7ed841", "style": "normal"}, {"source": "t_lateral_control_configuration", "target": "m_fw_lat_lon_control", "color": "#77d841", "style": "normal"}, {"source": "t_fixed_wing_lateral_setpoint", "target": "m_fw_lat_lon_control", "color": "#41d893", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_lat_lon_control", "color": "#d84175", "style": "normal"}, {"source": "t_flaps_setpoint", "target": "m_fw_lat_lon_control", "color": "#d84168", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_lat_lon_control", "color": "#4166d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_lat_lon_control", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_lat_lon_control", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_lat_lon_control", "color": "#b941d8", "style": "normal"}, {"source": "t_fixed_wing_longitudinal_setpoint", "target": "m_fw_lat_lon_control", "color": "#bf41d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_lat_lon_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_fw_mode_manager", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_mode_manager", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_mode_manager", "color": "#41d8ce", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_fw_mode_manager", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fw_mode_manager", "color": "#d84175", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_mode_manager", "color": "#4166d8", "style": "normal"}, {"source": "t_wind", "target": "m_fw_mode_manager", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_mode_manager", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_fw_mode_manager", "color": "#b941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_fw_mode_manager", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_fw_mode_manager", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_mode_manager", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_fw_rate_control", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_fw_rate_control", "color": "#71d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_fw_rate_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_fw_rate_control", "color": "#4179d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_fw_rate_control", "color": "#4166d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_fw_rate_control", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_fw_rate_control", "color": "#41d84b", "style": "normal"}, {"source": "t_battery_status", "target": "m_fw_rate_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_gimbal", "color": "#d87541", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_gimbal", "color": "#7ed841", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_gimbal", "color": "#d841ca", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_gimbal", "color": "#d84175", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gimbal", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_roi", "target": "m_gimbal", "color": "#418dd8", "style": "normal"}, {"source": "t_gimbal_manager_set_attitude", "target": "m_gimbal", "color": "#ab41d8", "style": "normal"}, {"source": "t_gimbal_manager_set_manual_control", "target": "m_gimbal", "color": "#d841b6", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_gimbal", "color": "#d84154", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_gimbal", "color": "#d86141", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gimbal", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_gyro_calibration", "color": "#41ced8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_gyro_calibration", "color": "#d88941", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_calibration", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_gyro_calibration", "color": "#41a7d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_gyro_fft", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_gyro_fft", "color": "#41d880", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_gyro_fft", "color": "#41d5d8", "style": "normal"}, {"source": "t_sensor_gyro_fifo", "target": "m_gyro_fft", "color": "#d88241", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_land_detector", "color": "#d87541", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_land_detector", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_land_detector", "color": "#41d5d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_land_detector", "color": "#8441d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_land_detector", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_land_detector", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_land_detector", "color": "#b941d8", "style": "normal"}, {"source": "t_takeoff_status", "target": "m_land_detector", "color": "#b2d841", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_land_detector", "color": "#4166d8", "style": "normal"}, {"source": "t_launch_detection_status", "target": "m_land_detector", "color": "#41c8d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_land_detector", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_land_detector", "color": "#41d879", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_land_detector", "color": "#41d880", "style": "normal"}, {"source": "t_irlock_report", "target": "m_landing_target_estimator", "color": "#5641d8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_landing_target_estimator", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_landing_target_estimator", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_visual_odometry", "target": "m_local_position_estimator", "color": "#414bd8", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_local_position_estimator", "color": "#7ed841", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_local_position_estimator", "color": "#41d88d", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_local_position_estimator", "color": "#d84175", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_local_position_estimator", "color": "#8441d8", "style": "normal"}, {"source": "t_sensor_combined", "target": "m_local_position_estimator", "color": "#d84196", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_local_position_estimator", "color": "#b941d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_local_position_estimator", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_local_position_estimator", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_mocap_odometry", "target": "m_local_position_estimator", "color": "#c641d8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_logger", "color": "#41d8ce", "style": "normal"}, {"source": "t_ulog_stream_ack", "target": "m_logger", "color": "#b241d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_logger", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_logger", "color": "#d8bd41", "style": "normal"}, {"source": "t_battery_status", "target": "m_logger", "color": "#7141d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mag_bias_estimator", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mag_bias_estimator", "color": "#41ced8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_manual_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_manual_control", "color": "#ccd841", "style": "normal"}, {"source": "t_action_request", "target": "m_manual_control", "color": "#d8418f", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_manual_control", "color": "#41ced8", "style": "normal"}, {"source": "t_dataman_response", "target": "m_mavlink", "color": "#d84141", "style": "normal"}, {"source": "t_figure_eight_status", "target": "m_mavlink", "color": "#d85b41", "style": "normal"}, {"source": "t_gimbal_device_attitude_status", "target": "m_mavlink", "color": "#d86141", "style": "normal"}, {"source": "t_estimator_status", "target": "m_mavlink", "color": "#d86841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_mavlink", "color": "#d87541", "style": "normal"}, {"source": "t_gps_inject_data", "target": "m_mavlink", "color": "#d87b41", "style": "normal"}, {"source": "t_mission", "target": "m_mavlink", "color": "#d88f41", "style": "normal"}, {"source": "t_orbit_status", "target": "m_mavlink", "color": "#d89641", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mavlink", "color": "#d89c41", "style": "normal"}, {"source": "t_satellite_info", "target": "m_mavlink", "color": "#d8a341", "style": "normal"}, {"source": "t_event", "target": "m_mavlink", "color": "#d8b041", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_mavlink", "color": "#d8bd41", "style": "normal"}, {"source": "t_debug_key_value", "target": "m_mavlink", "color": "#d8d141", "style": "normal"}, {"source": "t_input_rc", "target": "m_mavlink", "color": "#d8d741", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_mavlink", "color": "#ccd841", "style": "normal"}, {"source": "t_gimbal_manager_information", "target": "m_mavlink", "color": "#c6d841", "style": "normal"}, {"source": "t_gimbal_v1_command", "target": "m_mavlink", "color": "#bfd841", "style": "normal"}, {"source": "t_vehicle_odometry", "target": "m_mavlink", "color": "#9ed841", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_mavlink", "color": "#a5d841", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_mavlink", "color": "#abd841", "style": "normal"}, {"source": "t_transponder_report", "target": "m_mavlink", "color": "#91d841", "style": "normal"}, {"source": "t_sensor_gps", "target": "m_mavlink", "color": "#8bd841", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mavlink", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mavlink", "color": "#71d841", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_mavlink", "color": "#6ad841", "style": "normal"}, {"source": "t_camera_capture", "target": "m_mavlink", "color": "#63d841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_mavlink", "color": "#5dd841", "style": "normal"}, {"source": "t_health_report", "target": "m_mavlink", "color": "#56d841", "style": "normal"}, {"source": "t_wind", "target": "m_mavlink", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_angular_velocity_groundtruth", "target": "m_mavlink", "color": "#41d852", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mavlink", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_mavlink", "color": "#41d845", "style": "normal"}, {"source": "t_geofence_result", "target": "m_mavlink", "color": "#41d85f", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_mavlink", "color": "#41d866", "style": "normal"}, {"source": "t_vehicle_thrust_setpoint", "target": "m_mavlink", "color": "#41d879", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_mavlink", "color": "#41d880", "style": "normal"}, {"source": "t_distance_sensor", "target": "m_mavlink", "color": "#41d88d", "style": "normal"}, {"source": "t_esc_status", "target": "m_mavlink", "color": "#41d8a7", "style": "normal"}, {"source": "t_debug_array", "target": "m_mavlink", "color": "#41d8c1", "style": "normal"}, {"source": "t_tecs_status", "target": "m_mavlink", "color": "#41d8c8", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mavlink", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_mavlink", "color": "#41d5d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mavlink", "color": "#41ced8", "style": "normal"}, {"source": "t_airspeed", "target": "m_mavlink", "color": "#41bbd8", "style": "normal"}, {"source": "t_debug_vect", "target": "m_mavlink", "color": "#41aed8", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_mavlink", "color": "#41a7d8", "style": "normal"}, {"source": "t_home_position", "target": "m_mavlink", "color": "#41a1d8", "style": "normal"}, {"source": "t_gimbal_manager_status", "target": "m_mavlink", "color": "#4193d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_mavlink", "color": "#4186d8", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_mavlink", "color": "#4173d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_mavlink", "color": "#4166d8", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_mavlink", "color": "#415fd8", "style": "normal"}, {"source": "t_debug_value", "target": "m_mavlink", "color": "#4341d8", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mavlink", "color": "#5041d8", "style": "normal"}, {"source": "t_battery_status", "target": "m_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_ulog_stream", "target": "m_mavlink", "color": "#7741d8", "style": "normal"}, {"source": "t_failsafe_flags", "target": "m_mavlink", "color": "#7e41d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_mavlink", "color": "#8441d8", "style": "normal"}, {"source": "t_rpm", "target": "m_mavlink", "color": "#9141d8", "style": "normal"}, {"source": "t_mount_orientation", "target": "m_mavlink", "color": "#9841d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_mavlink", "color": "#a541d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mavlink", "color": "#b941d8", "style": "normal"}, {"source": "t_register_ext_component_reply", "target": "m_mavlink", "color": "#d341d8", "style": "normal"}, {"source": "t_mission_result", "target": "m_mavlink", "color": "#d841d7", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_mavlink", "color": "#d841d1", "style": "normal"}, {"source": "t_gimbal_device_information", "target": "m_mavlink", "color": "#d841ca", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_mavlink", "color": "#d841bd", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_mavlink", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_mavlink", "color": "#d841a9", "style": "normal"}, {"source": "t_cpuload", "target": "m_mavlink", "color": "#d841a3", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_mavlink", "color": "#d8419c", "style": "normal"}, {"source": "t_camera_status", "target": "m_mavlink", "color": "#d84189", "style": "normal"}, {"source": "t_rtl_time_estimate", "target": "m_mavlink", "color": "#d8417b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mavlink", "color": "#d84175", "style": "normal"}, {"source": "t_camera_trigger", "target": "m_mavlink", "color": "#d8415b", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_mavlink", "color": "#d84154", "style": "normal"}, {"source": "t_estimator_selector_status", "target": "m_mavlink", "color": "#d84147", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_att_control", "color": "#7ed841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_mc_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_mc_att_control", "color": "#5041d8", "style": "normal"}, {"source": "t_autotune_attitude_control_status", "target": "m_mc_att_control", "color": "#d89c41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_att_control", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_att_control", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_autotune_attitude_control", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_torque_setpoint", "target": "m_mc_autotune_attitude_control", "color": "#6341d8", "style": "normal"}, {"source": "t_actuator_controls_status_0", "target": "m_mc_autotune_attitude_control", "color": "#d8a941", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_pos_control", "color": "#7ed841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_mc_pos_control", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_mc_pos_control", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_constraints", "target": "m_mc_pos_control", "color": "#41d873", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_mc_rate_control", "color": "#7ed841", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_mc_rate_control", "color": "#71d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_mc_rate_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_control_allocator_status", "target": "m_mc_rate_control", "color": "#4179d8", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_mc_rate_control", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_mc_rate_control", "color": "#41d84b", "style": "normal"}, {"source": "t_battery_status", "target": "m_mc_rate_control", "color": "#7141d8", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_navigator", "color": "#d87541", "style": "normal"}, {"source": "t_transponder_report", "target": "m_navigator", "color": "#91d841", "style": "normal"}, {"source": "t_dataman_response", "target": "m_navigator", "color": "#d84141", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_navigator", "color": "#7ed841", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_navigator", "color": "#5dd841", "style": "normal"}, {"source": "t_mission", "target": "m_navigator", "color": "#d88f41", "style": "normal"}, {"source": "t_position_controller_landing_status", "target": "m_navigator", "color": "#50d841", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_navigator", "color": "#41ced8", "style": "normal"}, {"source": "t_wind", "target": "m_navigator", "color": "#43d841", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_navigator", "color": "#b941d8", "style": "normal"}, {"source": "t_landing_target_pose", "target": "m_navigator", "color": "#6ad841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_navigator", "color": "#d8bd41", "style": "normal"}, {"source": "t_geofence_status", "target": "m_navigator", "color": "#41d8b4", "style": "normal"}, {"source": "t_home_position", "target": "m_navigator", "color": "#41a1d8", "style": "normal"}, {"source": "t_rtl_status", "target": "m_navigator", "color": "#9e41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_payload_deliverer", "color": "#d8bd41", "style": "normal"}, {"source": "t_manual_control_switches", "target": "m_rc_update", "color": "#ccd841", "style": "normal"}, {"source": "t_rc_parameter_map", "target": "m_rc_update", "color": "#416cd8", "style": "normal"}, {"source": "t_input_rc", "target": "m_rc_update", "color": "#d8d741", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_ackermann", "color": "#4152d8", "style": "normal"}, {"source": "t_position_controller_status", "target": "m_rover_ackermann", "color": "#5dd841", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_ackermann", "color": "#b9d841", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_ackermann", "color": "#d84175", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_ackermann", "color": "#d8416e", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_ackermann", "color": "#41d8ce", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_ackermann", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_ackermann", "color": "#d84e41", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_ackermann", "color": "#5d41d8", "style": "normal"}, {"source": "t_actuator_servos", "target": "m_rover_ackermann", "color": "#41d86c", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_ackermann", "color": "#b941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_ackermann", "color": "#d84154", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_ackermann", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_ackermann", "color": "#41d84b", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_ackermann", "color": "#d86e41", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_ackermann", "color": "#d3d841", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_differential", "color": "#4152d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_differential", "color": "#b9d841", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_differential", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_differential", "color": "#d84175", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_differential", "color": "#41d8ce", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_differential", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_differential", "color": "#d84e41", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_differential", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_differential", "color": "#b941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_differential", "color": "#d84154", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_differential", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_differential", "color": "#41d84b", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_differential", "color": "#d86e41", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_differential", "color": "#d3d841", "style": "normal"}, {"source": "t_offboard_control_mode", "target": "m_rover_mecanum", "color": "#4152d8", "style": "normal"}, {"source": "t_rover_velocity_setpoint", "target": "m_rover_mecanum", "color": "#b9d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_mecanum", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_mecanum", "color": "#d84175", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_mecanum", "color": "#d8416e", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_rover_mecanum", "color": "#4180d8", "style": "normal"}, {"source": "t_rover_rate_setpoint", "target": "m_rover_mecanum", "color": "#d84e41", "style": "normal"}, {"source": "t_rover_attitude_setpoint", "target": "m_rover_mecanum", "color": "#5d41d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_mecanum", "color": "#b941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_mecanum", "color": "#d84154", "style": "normal"}, {"source": "t_rover_position_setpoint", "target": "m_rover_mecanum", "color": "#d8c441", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_mecanum", "color": "#41d84b", "style": "normal"}, {"source": "t_rover_steering_setpoint", "target": "m_rover_mecanum", "color": "#d86e41", "style": "normal"}, {"source": "t_rover_throttle_setpoint", "target": "m_rover_mecanum", "color": "#d3d841", "style": "normal"}, {"source": "t_vehicle_global_position", "target": "m_rover_pos_control", "color": "#d87541", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_rover_pos_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_rover_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_rover_pos_control", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_rover_pos_control", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_rover_pos_control", "color": "#b941d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_rover_pos_control", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_rover_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_imu", "target": "m_sensors", "color": "#d841a9", "style": "normal"}, {"source": "t_differential_pressure", "target": "m_sensors", "color": "#d841d1", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_sensors", "color": "#d88941", "style": "normal"}, {"source": "t_vehicle_imu_status", "target": "m_sensors", "color": "#41d5d8", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_sensors", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_optical_flow", "target": "m_sensors", "color": "#d8ca41", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_sensors", "color": "#abd841", "style": "normal"}, {"source": "t_estimator_sensor_bias", "target": "m_sensors", "color": "#41d866", "style": "normal"}, {"source": "t_sensor_correction", "target": "m_sensors", "color": "#41a7d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_sensors", "color": "#41d84b", "style": "normal"}, {"source": "t_sensor_selection", "target": "m_sensors", "color": "#41d880", "style": "normal"}, {"source": "t_flight_phase_estimation", "target": "m_battery_simulator", "color": "#8b41d8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_battery_simulator", "color": "#d8bd41", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_battery_simulator", "color": "#41ced8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_gz_bridge", "color": "#84d841", "style": "normal"}, {"source": "t_gripper", "target": "m_gz_bridge", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_gz_bridge", "color": "#41d8ce", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_gz_bridge", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_gz_bridge", "color": "#8441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_gz_bridge", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_gz_bridge", "color": "#d8bd41", "style": "normal"}, {"source": "t_gimbal_device_set_attitude", "target": "m_gz_bridge", "color": "#415fd8", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_gz_bridge", "color": "#6a41d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_gz_bridge", "color": "#41c1d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_gz_bridge", "color": "#41b4d8", "style": "normal"}, {"source": "t_actuator_test", "target": "m_pwm_out_sim", "color": "#84d841", "style": "normal"}, {"source": "t_gripper", "target": "m_pwm_out_sim", "color": "#41d89a", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_pwm_out_sim", "color": "#41d8ce", "style": "normal"}, {"source": "t_actuator_motors", "target": "m_pwm_out_sim", "color": "#4180d8", "style": "normal"}, {"source": "t_actuator_armed", "target": "m_pwm_out_sim", "color": "#8441d8", "style": "normal"}, {"source": "t_landing_gear", "target": "m_pwm_out_sim", "color": "#d84161", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_pwm_out_sim", "color": "#d8bd41", "style": "normal"}, {"source": "t_landing_gear_wheel", "target": "m_pwm_out_sim", "color": "#6a41d8", "style": "normal"}, {"source": "t_actuator_servos_trim", "target": "m_pwm_out_sim", "color": "#41c1d8", "style": "normal"}, {"source": "t_gimbal_controls", "target": "m_pwm_out_sim", "color": "#41b4d8", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_agp_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#a5d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_airspeed_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_sensor_airspeed_sim", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_baro_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_local_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#a5d841", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_gps_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_global_position_groundtruth", "target": "m_sensor_mag_sim", "color": "#d8419c", "style": "normal"}, {"source": "t_vehicle_attitude_groundtruth", "target": "m_sensor_mag_sim", "color": "#4173d8", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_mavlink", "color": "#a541d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_mavlink", "color": "#d841bd", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_simulator_mavlink", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_simulator_mavlink", "color": "#d8bd41", "style": "normal"}, {"source": "t_battery_status", "target": "m_simulator_mavlink", "color": "#7141d8", "style": "normal"}, {"source": "t_actuator_outputs_sim", "target": "m_simulator_sih", "color": "#d841bd", "style": "normal"}, {"source": "t_actuator_outputs", "target": "m_simulator_sih", "color": "#a541d8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_temperature_compensation", "color": "#d88941", "style": "normal"}, {"source": "t_sensor_gyro", "target": "m_temperature_compensation", "color": "#4941d8", "style": "normal"}, {"source": "t_sensor_mag", "target": "m_temperature_compensation", "color": "#abd841", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_temperature_compensation", "color": "#d8bd41", "style": "normal"}, {"source": "t_sensor_baro", "target": "m_temperature_compensation", "color": "#d841b0", "style": "normal"}, {"source": "t_vehicle_rates_setpoint", "target": "m_uuv_att_control", "color": "#71d841", "style": "normal"}, {"source": "t_manual_control_setpoint", "target": "m_uuv_att_control", "color": "#41d8ce", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_attitude_setpoint", "target": "m_uuv_att_control", "color": "#5041d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_uuv_pos_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_uuv_pos_control", "color": "#41d84b", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_uuv_pos_control", "color": "#b941d8", "style": "normal"}, {"source": "t_trajectory_setpoint", "target": "m_uuv_pos_control", "color": "#d8416e", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_uxrce_dds_client", "color": "#41d845", "style": "normal"}, {"source": "t_vehicle_local_position", "target": "m_vtol_att_control", "color": "#b941d8", "style": "normal"}, {"source": "t_vehicle_control_mode", "target": "m_vtol_att_control", "color": "#41d84b", "style": "normal"}, {"source": "t_home_position", "target": "m_vtol_att_control", "color": "#41a1d8", "style": "normal"}, {"source": "t_vehicle_local_position_setpoint", "target": "m_vtol_att_control", "color": "#4186d8", "style": "normal"}, {"source": "t_airspeed_validated", "target": "m_vtol_att_control", "color": "#4166d8", "style": "normal"}, {"source": "t_position_setpoint_triplet", "target": "m_vtol_att_control", "color": "#d84154", "style": "normal"}, {"source": "t_vehicle_command", "target": "m_vtol_att_control", "color": "#d8bd41", "style": "normal"}, {"source": "t_mc_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#41d886", "style": "normal"}, {"source": "t_action_request", "target": "m_vtol_att_control", "color": "#d8418f", "style": "normal"}, {"source": "t_fw_virtual_attitude_setpoint", "target": "m_vtol_att_control", "color": "#d84182", "style": "normal"}, {"source": "t_vehicle_land_detected", "target": "m_vtol_att_control", "color": "#7ed841", "style": "normal"}, {"source": "t_tecs_status", "target": "m_vtol_att_control", "color": "#41d8c8", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_vtol_att_control", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_vtol_att_control", "color": "#41ced8", "style": "normal"}, {"source": "t_vehicle_command_ack", "target": "m_failure", "color": "#41d845", "style": "normal"}, {"source": "t_dataman_response", "target": "m_tests", "color": "#d84141", "style": "normal"}, {"source": "t_input_rc", "target": "m_tests", "color": "#d8d741", "style": "normal"}, {"source": "t_vehicle_attitude", "target": "m_fake_magnetometer", "color": "#d84175", "style": "normal"}, {"source": "t_vehicle_status", "target": "m_work_item_example", "color": "#41ced8", "style": "normal"}, {"source": "t_sensor_accel", "target": "m_work_item_example", "color": "#d88941", "style": "normal"}]} \ No newline at end of file